diff options
Diffstat (limited to 'host/lib/usrp')
107 files changed, 4562 insertions, 7242 deletions
| diff --git a/host/lib/usrp/CMakeLists.txt b/host/lib/usrp/CMakeLists.txt index 45498e3b4..8ae379f73 100644 --- a/host/lib/usrp/CMakeLists.txt +++ b/host/lib/usrp/CMakeLists.txt @@ -24,17 +24,15 @@ LIBUHD_APPEND_SOURCES(      ${CMAKE_CURRENT_SOURCE_DIR}/dboard_id.cpp      ${CMAKE_CURRENT_SOURCE_DIR}/dboard_iface.cpp      ${CMAKE_CURRENT_SOURCE_DIR}/dboard_manager.cpp -    ${CMAKE_CURRENT_SOURCE_DIR}/dsp_utils.cpp      ${CMAKE_CURRENT_SOURCE_DIR}/gps_ctrl.cpp      ${CMAKE_CURRENT_SOURCE_DIR}/mboard_eeprom.cpp -    ${CMAKE_CURRENT_SOURCE_DIR}/misc_utils.cpp      ${CMAKE_CURRENT_SOURCE_DIR}/multi_usrp.cpp      ${CMAKE_CURRENT_SOURCE_DIR}/subdev_spec.cpp -    ${CMAKE_CURRENT_SOURCE_DIR}/tune_helper.cpp  ) +INCLUDE_SUBDIRECTORY(cores)  INCLUDE_SUBDIRECTORY(dboard) -INCLUDE_SUBDIRECTORY(fx2) +INCLUDE_SUBDIRECTORY(common)  INCLUDE_SUBDIRECTORY(usrp1)  INCLUDE_SUBDIRECTORY(usrp2)  INCLUDE_SUBDIRECTORY(b100) 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..5b03fd591 100644 --- a/host/lib/usrp/b100/b100_ctrl.cpp +++ b/host/lib/usrp/b100/b100_ctrl.cpp @@ -15,9 +15,8 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include "../../transport/super_recv_packet_handler.hpp"  #include "b100_ctrl.hpp" -#include "b100_impl.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> @@ -36,9 +35,8 @@ 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),          _seq(0)      { @@ -46,29 +44,65 @@ 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]); +    } + +    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(boost::barrier &);      bounded_buffer<ctrl_data_t> sync_ctrl_fifo; -    bounded_buffer<async_metadata_t> async_msg_fifo; +    async_cb_type _async_cb;      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, _async_mutex;  };  /*********************************************************************** @@ -86,7 +120,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 +133,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 +147,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 +166,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; @@ -149,11 +183,18 @@ ctrl_data_t b100_ctrl_impl::read(boost::uint32_t addr, size_t 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); -     -    //loop around waiting for the response to appear -    while(!get_ctrl_data(pkt.data, 0.05)); + +    //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;  } @@ -168,55 +209,38 @@ 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! +        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)) { -                throw uhd::runtime_error("Sequence error on control channel"); +                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)) { -                throw uhd::runtime_error("Control channel packet length too long"); +                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_wait(pkt.data); -        } else { //it's an async status pkt -            //extract the vrt header packet info -            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 *>(); -            vrt::if_hdr_unpack_le(vrt_hdr, if_packet_info); -             -            if(    if_packet_info.sid == B100_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; -                metadata.channel = 0; -                metadata.has_time_spec = if_packet_info.has_tsi and if_packet_info.has_tsf; -                metadata.time_spec = time_spec_t( -                    time_t(if_packet_info.tsi), size_t(if_packet_info.tsf), 64e6 //FIXME get from clock_ctrl -                ); -                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_IN_PACKET) -                ) UHD_MSG(fastpath) << "U"; -                else if (metadata.event_code & -                    ( async_metadata_t::EVENT_CODE_SEQ_ERROR -                    | async_metadata_t::EVENT_CODE_SEQ_ERROR_IN_BURST) -                ) UHD_MSG(fastpath) << "S"; -                continue; -            } -            UHD_MSG(error) << "Control: unknown async response" << std::endl; +            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);          }      }  } @@ -226,14 +250,9 @@ bool b100_ctrl_impl::get_ctrl_data(ctrl_data_t &pkt_data, double timeout){      return sync_ctrl_fifo.pop_with_timed_wait(pkt_data, timeout);  } -bool b100_ctrl_impl::recv_async_msg(uhd::async_metadata_t &async_metadata, double timeout) { -    boost::this_thread::disable_interruption di; //disable because the wait can throw -    return async_msg_fifo.pop_with_timed_wait(async_metadata, timeout); -} -  /***********************************************************************   * 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..74884d525 100644 --- a/host/lib/usrp/b100/b100_ctrl.hpp +++ b/host/lib/usrp/b100/b100_ctrl.hpp @@ -18,25 +18,28 @@  #ifndef INCLUDED_B100_CTRL_HPP  #define INCLUDED_B100_CTRL_HPP -#include <uhd/transport/bounded_buffer.hpp> +#include "wb_iface.hpp"  #include <uhd/transport/usb_zero_copy.hpp> -#include <uhd/types/metadata.hpp>  #include <uhd/types/serial.hpp>  #include <boost/shared_ptr.hpp>  #include <boost/utility.hpp>  #include "ctrl_packet.hpp" -#include <boost/thread.hpp> +#include <boost/function.hpp> -class b100_ctrl : boost::noncopyable{ +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::usb_zero_copy::sptr ctrl_transport); +    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 @@ -61,9 +64,7 @@ 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.cpp b/host/lib/usrp/b100/b100_iface.cpp deleted file mode 100644 index f0e241541..000000000 --- a/host/lib/usrp/b100/b100_iface.cpp +++ /dev/null @@ -1,335 +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_impl.hpp" -#include "usrp_commands.h" -#include <uhd/exception.hpp> -#include <uhd/utils/byteswap.hpp> -#include <uhd/utils/safe_call.hpp> -#include <uhd/utils/msg.hpp> -#include <boost/format.hpp> -#include <iomanip> -#include <iostream> - -//FOR TESTING ONLY -#include "b100_regs.hpp" -#include <boost/thread/thread.hpp> -#include "usrp_i2c_addr.h" - -using namespace uhd; -using namespace uhd::usrp; -using namespace uhd::transport; - -/*********************************************************************** - * Constants - **********************************************************************/ -static const bool iface_debug = true; - -/*********************************************************************** - * I2C + FX2 implementation wrapper - **********************************************************************/ -class b100_i2c_fx2_iface : public i2c_iface{ -public: -    b100_i2c_fx2_iface(uhd::usrp::fx2_ctrl::sptr fx2_ctrl){ -        _fx2_ctrl = fx2_ctrl; -    } - -    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 = _fx2_ctrl->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 = _fx2_ctrl->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: -    static const size_t max_i2c_data_bytes = 64; -    uhd::usrp::fx2_ctrl::sptr _fx2_ctrl; -}; - -/*********************************************************************** - * USRP-E100 interface implementation - **********************************************************************/ -class b100_iface_impl : public b100_iface{ -public: -    /******************************************************************* -     * Structors -     ******************************************************************/ -    b100_iface_impl(uhd::usrp::fx2_ctrl::sptr fx2_ctrl, -                      b100_ctrl::sptr fpga_ctrl) : -                      _fx2_i2c_iface(fx2_ctrl), -                      _fx2_ctrl(fx2_ctrl), -                      _fpga_ctrl(fpga_ctrl) -    { -        this->check_fw_compat(); -        if (fpga_ctrl.get() != NULL){ -            enable_gpif(1); -            i2c_init(); -            this->check_fpga_compat(); -        } -        mb_eeprom = mboard_eeprom_t(get_fx2_i2c_iface(), mboard_eeprom_t::MAP_B000); -    } - -    void 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)); -        } -    } - -    void check_fpga_compat(void){ -        const boost::uint16_t fpga_compat_num = this->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_iface_impl(void) -    { -        /* NOP */ -    } - -    /******************************************************************* -     * Peek and Poke -     ******************************************************************/ - -    void poke(boost::uint32_t addr, const ctrl_data_t &data) { -        boost::mutex::scoped_lock lock(_ctrl_mutex); -        _fpga_ctrl->write(addr, data); -    } - -    ctrl_data_t peek(boost::uint32_t addr, size_t len) { -        boost::mutex::scoped_lock lock(_ctrl_mutex); -        return _fpga_ctrl->read(addr, len); -    } - -    void poke16(boost::uint32_t addr, boost::uint16_t value) -    { -        ctrl_data_t words(1); -        words[0] = value; -        poke(addr, words); -    } - -    void poke32(boost::uint32_t addr, boost::uint32_t value) -    { -        //just a subset of poke() to maintain compatibility -        ctrl_data_t words(2); -        words[0] = value & 0x0000FFFF; -        words[1] = value >> 16; -        poke(addr, words); -    } - -    boost::uint32_t peek32(boost::uint32_t addr) -    { -        ctrl_data_t words = peek(addr, 2); -        return boost::uint32_t((boost::uint32_t(words[1]) << 16) | words[0]); -    } - -    boost::uint16_t peek16(boost::uint32_t addr) -    { -        ctrl_data_t words = peek(addr, 1); -        return boost::uint16_t(words[0]); -    } - -    /******************************************************************* -     * I2C -     ******************************************************************/ -    static const boost::uint32_t i2c_datarate = 400000; -    static const boost::uint32_t wishbone_clk = 64000000; //FIXME should go somewhere else - -    void i2c_init(void) { -        //init I2C FPGA interface. -        poke16(B100_REG_I2C_CTRL, 0x0000); -        //set prescalers to operate at 400kHz: WB_CLK is 64MHz... -        boost::uint16_t prescaler = wishbone_clk / (i2c_datarate*5) - 1; -        poke16(B100_REG_I2C_PRESCALER_LO, prescaler & 0xFF); -        poke16(B100_REG_I2C_PRESCALER_HI, (prescaler >> 8) & 0xFF); -        poke16(B100_REG_I2C_CTRL, I2C_CTRL_EN); //enable I2C core -    } - -    static const size_t max_i2c_data_bytes = 64; - -    void i2c_wait_for_xfer(void) -    { -        while(this->peek16(B100_REG_I2C_CMD_STATUS) & I2C_ST_TIP) -            boost::this_thread::sleep(boost::posix_time::milliseconds(10)); -    } - -    bool wait_chk_ack(void) { -        i2c_wait_for_xfer(); -        return (this->peek16(B100_REG_I2C_CMD_STATUS) & I2C_ST_RXACK) == 0; -    } - -    void write_i2c(boost::uint8_t addr, const byte_vector_t &bytes) -    { -        poke16(B100_REG_I2C_DATA, (addr << 1) | 0); //addr and read bit (0) -        poke16(B100_REG_I2C_CMD_STATUS, I2C_CMD_WR | I2C_CMD_START | (bytes.size() == 0 ? I2C_CMD_STOP : 0)); - -        //wait for previous transfer to complete -        if(!wait_chk_ack()) { -            poke16(B100_REG_I2C_CMD_STATUS, I2C_CMD_STOP); -            return; -        } - -        for(size_t i = 0; i < bytes.size(); i++) { -            poke16(B100_REG_I2C_DATA, bytes[i]); -            poke16(B100_REG_I2C_CMD_STATUS, I2C_CMD_WR | ((i == (bytes.size() - 1)) ? I2C_CMD_STOP : 0)); -            if(!wait_chk_ack()) { -                poke16(B100_REG_I2C_CMD_STATUS, I2C_CMD_STOP); -                return; -            } -        } -    } - -    byte_vector_t read_i2c(boost::uint8_t addr, size_t num_bytes) -    { -        byte_vector_t bytes; -        if(num_bytes == 0) return bytes; - -        while (peek16(B100_REG_I2C_CMD_STATUS) & I2C_ST_BUSY); - -        poke16(B100_REG_I2C_DATA, (addr << 1) | 1); //addr and read bit (1) -        poke16(B100_REG_I2C_CMD_STATUS, I2C_CMD_WR | I2C_CMD_START); -        //wait for previous transfer to complete -        if(!wait_chk_ack()) { -            poke16(B100_REG_I2C_CMD_STATUS, I2C_CMD_STOP); -        } - -        for(; num_bytes > 0; num_bytes--) { -            poke16(B100_REG_I2C_CMD_STATUS, I2C_CMD_RD | ((num_bytes == 1) ? (I2C_CMD_STOP | I2C_CMD_NACK) : 0)); -            i2c_wait_for_xfer(); -            boost::uint8_t readback = peek16(B100_REG_I2C_DATA) & 0xFF; -            bytes.push_back(readback); -        } -        return bytes; -    } - -    i2c_iface &get_fx2_i2c_iface(void){ -        return _fx2_i2c_iface; -    } - -    /******************************************************************* -     * SPI interface -     * Eventually this will be replaced with a control-channel system -     * to let the firmware do the actual write/readback cycles. -     * This keeps the bandwidth on the control channel down. -     ******************************************************************/ - -    void spi_wait(void) { -        while(peek32(B100_REG_SPI_CTRL) & SPI_CTRL_GO_BSY); -    } - -    boost::uint32_t transact_spi(int which_slave, -                                 const spi_config_t &config, -                                 boost::uint32_t bits, -                                 size_t num_bits, -                                 bool readback) -    { -        UHD_ASSERT_THROW((num_bits <= 32) && !(num_bits % 8)); - -        int edge_flags = ((config.miso_edge==spi_config_t::EDGE_FALL) ? SPI_CTRL_RXNEG : 0) | -                         ((config.mosi_edge==spi_config_t::EDGE_FALL) ? 0 : SPI_CTRL_TXNEG) -                         ; - -        boost::uint16_t ctrl = SPI_CTRL_ASS | (SPI_CTRL_CHAR_LEN_MASK & num_bits) | edge_flags; - -        spi_wait(); -        poke16(B100_REG_SPI_DIV, 0x0001); // = fpga_clk / 4 -        poke32(B100_REG_SPI_SS, which_slave & 0xFFFF); -        poke32(B100_REG_SPI_TXRX0, bits); -        poke16(B100_REG_SPI_CTRL, ctrl); - -        poke16(B100_REG_SPI_CTRL, ctrl | SPI_CTRL_GO_BSY); -        if(readback) { -            spi_wait(); -            return peek32(B100_REG_SPI_TXRX0); -        } -        else { -            return 0; -        } -    } - -    void reset_gpif(boost::uint16_t ep) { -        _fx2_ctrl->usrp_control_write(VRQ_RESET_GPIF, ep, ep, 0, 0); -    } - -    void enable_gpif(bool en) { -        _fx2_ctrl->usrp_control_write(VRQ_ENABLE_GPIF, en ? 1 : 0, 0, 0, 0); -    } - -    void clear_fpga_fifo(void) { -        _fx2_ctrl->usrp_control_write(VRQ_CLEAR_FPGA_FIFO, 0, 0, 0, 0); -    } - -    void write_uart(boost::uint8_t, const std::string &) { -        throw uhd::not_implemented_error("Unhandled command write_uart()"); -    } -     -    std::string read_uart(boost::uint8_t) { -        throw uhd::not_implemented_error("Unhandled command read_uart()"); -    } - -private: -    b100_i2c_fx2_iface _fx2_i2c_iface; -    uhd::usrp::fx2_ctrl::sptr _fx2_ctrl; -    b100_ctrl::sptr _fpga_ctrl; -    boost::mutex _ctrl_mutex; -}; - -/*********************************************************************** - * Public Make Function - **********************************************************************/ -b100_iface::sptr b100_iface::make(uhd::usrp::fx2_ctrl::sptr fx2_ctrl, -                                      b100_ctrl::sptr fpga_ctrl) -{ -    return b100_iface::sptr(new b100_iface_impl(fx2_ctrl, fpga_ctrl)); -} diff --git a/host/lib/usrp/b100/b100_iface.hpp b/host/lib/usrp/b100/b100_iface.hpp deleted file mode 100644 index a98db98dc..000000000 --- a/host/lib/usrp/b100/b100_iface.hpp +++ /dev/null @@ -1,78 +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_IFACE_HPP -#define INCLUDED_B100_IFACE_HPP - -#include <uhd/usrp/mboard_iface.hpp> -#include <uhd/usrp/mboard_eeprom.hpp> -#include <boost/shared_ptr.hpp> -#include <boost/utility.hpp> -#include <uhd/transport/usb_zero_copy.hpp> -#include "../fx2/fx2_ctrl.hpp" -#include "b100_ctrl.hpp" - -/*! - * The usrp1 interface class: - * Provides a set of functions to implementation layer. - * Including spi, peek, poke, control... - */ -class b100_iface : boost::noncopyable, public uhd::usrp::mboard_iface{ -public: -    typedef boost::shared_ptr<b100_iface> sptr; - -    /*! -     * Make a new b100 interface with the control transport. -     * \param fx2_ctrl the usrp control object -     * \param fpga_ctrl the FPGA interface control object -     * \return a new usrp1 interface object -     */ -    static sptr make(uhd::usrp::fx2_ctrl::sptr fx2_ctrl, -                     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 -     * \return -     */ -    virtual void reset_gpif(boost::uint16_t ep) = 0; - -    /*! -     * Clear the GPIF FIFOs on the FPGA -     * \return -     */ -    virtual void clear_fpga_fifo(void) = 0; - -    /*! -     * Enable/disable the GPIF interfaces on the FX2 -     * \return -     */ -    virtual void enable_gpif(bool en) = 0; - -    //! Get access to the FX2 I2C interface -    virtual uhd::i2c_iface &get_fx2_i2c_iface(void) = 0; - -    uhd::usrp::mboard_eeprom_t mb_eeprom; -}; - -#endif /* INCLUDED_USRP1_IFACE_HPP */ diff --git a/host/lib/usrp/b100/b100_impl.cpp b/host/lib/usrp/b100/b100_impl.cpp index d8c5e72ce..b58e70694 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,11 @@ 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);      device_addr_t data_xport_args;      data_xport_args["recv_frame_size"] = device_addr.get("recv_frame_size", "16384"); @@ -159,7 +172,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 +188,280 @@ 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 clock interface -    _clock_ctrl = b100_clock_ctrl::make(_iface, master_clock_rate); +    //////////////////////////////////////////////////////////////////// +    // Create controller objects +    //////////////////////////////////////////////////////////////////// +    _fpga_ctrl = b100_ctrl::make(_ctrl_transport); +    this->enable_gpif(true); //TODO best place to put this? +    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)"); +    _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_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++){ +        _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)); +        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 codec interface -    _codec_ctrl = b100_codec_ctrl::make(_iface); +    //////////////////////////////////////////////////////////////////// +    // 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 +    ); +    _tx_dsp->set_link_rate(B100_LINK_RATE_BPS); +    _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 / "clock_source/value") +        .subscribe(boost::bind(&b100_impl::update_clock_source, this, _1)); +    static const std::vector<std::string> clock_sources = boost::assign::list_of("internal")("external")("auto"); +    _tree->create<std::vector<std::string> >(mb_path / "clock_source/options").set(clock_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) +        ); +    } -    //initialize the codecs -    codec_init(); +    //initialize io handling +    this->io_init(); -    //initialize the mboard -    mboard_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 dboards -    dboard_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 dsps -    dsp_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 / "clock_source/value").set("internal"); +    _tree->access<std::string>(mb_path / "time_source/value").set("none"); +} -    //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()); +b100_impl::~b100_impl(void){ +    //set an empty async callback now that we deconstruct +    _fpga_ctrl->set_async_cb(b100_ctrl::async_cb_type()); +} -    //initialize the send/recv buffs -    io_init(); +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)); +    }  } -b100_impl::~b100_impl(void){ -    /* NOP */ +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)); +    }  } -bool b100_impl::recv_async_msg(uhd::async_metadata_t &md, double timeout){ -    return _fpga_ctrl->recv_async_msg(md, timeout); +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');  } -/*********************************************************************** - * 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_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){ +    mb_eeprom.commit(*_fx2_ctrl, mboard_eeprom_t::MAP_B000); +} -    //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::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); +} -    case DEVICE_PROP_MBOARD: -        UHD_ASSERT_THROW(key.name == ""); -        val = _mboard_proxy->get_link(); -        return; +void b100_impl::update_clock_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 == "external") _clock_ctrl->use_external_ref(); +    else throw uhd::runtime_error("unhandled clock configuration reference source: " + source); +} -    case DEVICE_PROP_MBOARD_NAMES: -        val = prop_names_t(1, ""); //vector of size 1 with empty string -        return; +////////////////// some GPIF preparation related stuff ///////////////// +void b100_impl::reset_gpif(const boost::uint16_t ep) { +    _fx2_ctrl->usrp_control_write(VRQ_RESET_GPIF, ep, ep, 0, 0); +} -    default: UHD_THROW_PROP_GET_ERROR(); -    } +void b100_impl::enable_gpif(const bool en) { +    _fx2_ctrl->usrp_control_write(VRQ_ENABLE_GPIF, en ? 1 : 0, 0, 0, 0);  } -/*********************************************************************** - * Device Set - **********************************************************************/ -void b100_impl::set(const wax::obj &, const wax::obj &) -{ -    UHD_THROW_PROP_SET_ERROR(); +void b100_impl::clear_fpga_fifo(void) { +    _fx2_ctrl->usrp_control_write(VRQ_CLEAR_FPGA_FIFO, 0, 0, 0, 0);  } diff --git a/host/lib/usrp/b100/b100_impl.hpp b/host/lib/usrp/b100/b100_impl.hpp index 2cea57eb5..62a22674e 100644 --- a/host/lib/usrp/b100/b100_impl.hpp +++ b/host/lib/usrp/b100/b100_impl.hpp @@ -15,83 +15,56 @@  // 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_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.bin"; +static const double          B100_LINK_RATE_BPS = 256e6/8; //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 = 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 +73,62 @@ 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_clock_source(const std::string &); +    void reset_gpif(const boost::uint16_t); +    void enable_gpif(const bool); +    void clear_fpga_fifo(void); +    void handle_async_message(uhd::transport::managed_recv_buffer::sptr);  };  #endif /* INCLUDED_b100_IMPL_HPP */ diff --git a/host/lib/usrp/b100/b100_regs.hpp b/host/lib/usrp/b100/b100_regs.hpp index 06288e875..5e24f9937 100644 --- a/host/lib/usrp/b100/b100_regs.hpp +++ b/host/lib/usrp/b100/b100_regs.hpp @@ -10,8 +10,8 @@  //  This means that address bit 0 is usually 0.  //  There are 11 bits of address for the control. -#ifndef __B100_REGS_H -#define __B100_REGS_H +#ifndef INCLUDED_B100_REGS_HPP +#define INCLUDED_B100_REGS_HPP  /////////////////////////////////////////////////////  // Slave pointers @@ -50,64 +50,16 @@  //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 B100_REG_SPI_TXRX0 B100_REG_SPI_BASE + 0 -#define B100_REG_SPI_TXRX1 B100_REG_SPI_BASE + 4 -#define B100_REG_SPI_TXRX2 B100_REG_SPI_BASE + 8 -#define B100_REG_SPI_TXRX3 B100_REG_SPI_BASE + 12 -#define B100_REG_SPI_CTRL  B100_REG_SPI_BASE + 16 -#define B100_REG_SPI_DIV   B100_REG_SPI_BASE + 20 -#define B100_REG_SPI_SS    B100_REG_SPI_BASE + 24  //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) -//spi ctrl register bit definitions -#define SPI_CTRL_ASS      (1<<13) -#define SPI_CTRL_IE       (1<<12) -#define SPI_CTRL_LSB      (1<<11) -#define SPI_CTRL_TXNEG    (1<<10) //mosi edge, push on falling edge when 1 -#define SPI_CTRL_RXNEG    (1<< 9) //miso edge, latch on falling edge when 1 -#define SPI_CTRL_GO_BSY   (1<< 8) -#define SPI_CTRL_CHAR_LEN_MASK 0x7F -  ////////////////////////////////////////////////  // Slave 3 -- I2C Core  #define B100_REG_I2C_BASE B100_REG_SLAVE(3) -#define B100_REG_I2C_PRESCALER_LO B100_REG_I2C_BASE + 0 -#define B100_REG_I2C_PRESCALER_HI B100_REG_I2C_BASE + 2 -#define B100_REG_I2C_CTRL         B100_REG_I2C_BASE + 4 -#define B100_REG_I2C_DATA         B100_REG_I2C_BASE + 6 -#define B100_REG_I2C_CMD_STATUS   B100_REG_I2C_BASE + 8 - -//and while we're here... - -// -// STA, STO, RD, WR, and IACK bits are cleared automatically -// - -#define	I2C_CTRL_EN	(1 << 7)	// core enable -#define	I2C_CTRL_IE	(1 << 6)	// interrupt enable - -#define	I2C_CMD_START	(1 << 7)	// generate (repeated) start condition -#define I2C_CMD_STOP	(1 << 6)	// generate stop condition -#define	I2C_CMD_RD	(1 << 5)	// read from slave -#define I2C_CMD_WR	(1 << 4)	// write to slave -#define	I2C_CMD_NACK	(1 << 3)	// when a rcvr, send ACK (ACK=0) or NACK (ACK=1) -#define I2C_CMD_RSVD_2	(1 << 2)	// reserved -#define	I2C_CMD_RSVD_1	(1 << 1)	// reserved -#define I2C_CMD_IACK	(1 << 0)	// set to clear pending interrupt - -#define I2C_ST_RXACK	(1 << 7)	// Received acknowledgement from slave (1 = NAK, 0 = ACK) -#define	I2C_ST_BUSY	(1 << 6)	// 1 after START signal detected; 0 after STOP signal detected -#define	I2C_ST_AL	(1 << 5)	// Arbitration lost.  1 when core lost arbitration -#define	I2C_ST_RSVD_4	(1 << 4)	// reserved -#define	I2C_ST_RSVD_3	(1 << 3)	// reserved -#define	I2C_ST_RSVD_2	(1 << 2)	// reserved -#define I2C_ST_TIP	(1 << 1)	// Transfer-in-progress -#define	I2C_ST_IP	(1 << 0)	// Interrupt pending  ////////////////////////////////////////////////  // Slave 4 -- GPIO @@ -191,94 +143,5 @@  #define B100_REG_CLEAR_TX           B100_REG_SR_ADDR(B100_SR_CLEAR_RX_FIFO)  #define B100_REG_GLOBAL_RESET       B100_REG_SR_ADDR(B100_SR_GLOBAL_RESET) -///////////////////////////////////////////////// -// DSP RX Regs -//////////////////////////////////////////////// -#define B100_REG_DSP_RX_HELPER(which, offset) ((which == 0)? \ -    (B100_REG_SR_ADDR(B100_SR_RX_DSP0 + offset)) : \ -    (B100_REG_SR_ADDR(B100_SR_RX_DSP1 + offset))) - -#define B100_REG_DSP_RX_FREQ(which)       B100_REG_DSP_RX_HELPER(which, 0) -#define B100_REG_DSP_RX_DECIM(which)      B100_REG_DSP_RX_HELPER(which, 2) -#define B100_REG_DSP_RX_MUX(which)        B100_REG_DSP_RX_HELPER(which, 3) - -#define B100_FLAG_DSP_RX_MUX_SWAP_IQ   (1 << 0) -#define B100_FLAG_DSP_RX_MUX_REAL_MODE (1 << 1) - -/////////////////////////////////////////////////// -// RX CTRL regs -/////////////////////////////////////////////////// -#define B100_REG_RX_CTRL_HELPER(which, offset) ((which == 0)? \ -    (B100_REG_SR_ADDR(B100_SR_RX_CTRL0 + offset)) : \ -    (B100_REG_SR_ADDR(B100_SR_RX_CTRL1 + offset))) - -#define B100_REG_RX_CTRL_STREAM_CMD(which)     B100_REG_RX_CTRL_HELPER(which, 0) -#define B100_REG_RX_CTRL_TIME_SECS(which)      B100_REG_RX_CTRL_HELPER(which, 1) -#define B100_REG_RX_CTRL_TIME_TICKS(which)     B100_REG_RX_CTRL_HELPER(which, 2) -#define B100_REG_RX_CTRL_CLEAR(which)          B100_REG_RX_CTRL_HELPER(which, 3) -#define B100_REG_RX_CTRL_VRT_HDR(which)        B100_REG_RX_CTRL_HELPER(which, 4) -#define B100_REG_RX_CTRL_VRT_SID(which)        B100_REG_RX_CTRL_HELPER(which, 5) -#define B100_REG_RX_CTRL_VRT_TLR(which)        B100_REG_RX_CTRL_HELPER(which, 6) -#define B100_REG_RX_CTRL_NSAMPS_PP(which)      B100_REG_RX_CTRL_HELPER(which, 7) -#define B100_REG_RX_CTRL_NCHANNELS(which)      B100_REG_RX_CTRL_HELPER(which, 8) - -///////////////////////////////////////////////// -// RX FE -//////////////////////////////////////////////// -#define B100_REG_RX_FE_SWAP_IQ             B100_REG_SR_ADDR(B100_SR_RX_FRONT + 0) //lower bit -#define B100_REG_RX_FE_MAG_CORRECTION      B100_REG_SR_ADDR(B100_SR_RX_FRONT + 1) //18 bits -#define B100_REG_RX_FE_PHASE_CORRECTION    B100_REG_SR_ADDR(B100_SR_RX_FRONT + 2) //18 bits -#define B100_REG_RX_FE_OFFSET_I            B100_REG_SR_ADDR(B100_SR_RX_FRONT + 3) //18 bits -#define B100_REG_RX_FE_OFFSET_Q            B100_REG_SR_ADDR(B100_SR_RX_FRONT + 4) //18 bits - -///////////////////////////////////////////////// -// DSP TX Regs -//////////////////////////////////////////////// -#define B100_REG_DSP_TX_FREQ          B100_REG_SR_ADDR(B100_SR_TX_DSP + 0) -#define B100_REG_DSP_TX_SCALE_IQ      B100_REG_SR_ADDR(B100_SR_TX_DSP + 1) -#define B100_REG_DSP_TX_INTERP_RATE   B100_REG_SR_ADDR(B100_SR_TX_DSP + 2) - -/////////////////////////////////////////////////// -// TX CTRL regs -/////////////////////////////////////////////////// -#define B100_REG_TX_CTRL_NUM_CHAN       B100_REG_SR_ADDR(B100_SR_TX_CTRL + 0) -#define B100_REG_TX_CTRL_CLEAR_STATE    B100_REG_SR_ADDR(B100_SR_TX_CTRL + 1) -#define B100_REG_TX_CTRL_REPORT_SID     B100_REG_SR_ADDR(B100_SR_TX_CTRL + 2) -#define B100_REG_TX_CTRL_POLICY         B100_REG_SR_ADDR(B100_SR_TX_CTRL + 3) -#define B100_REG_TX_CTRL_CYCLES_PER_UP  B100_REG_SR_ADDR(B100_SR_TX_CTRL + 4) -#define B100_REG_TX_CTRL_PACKETS_PER_UP B100_REG_SR_ADDR(B100_SR_TX_CTRL + 5) - -#define B100_FLAG_TX_CTRL_POLICY_WAIT          (0x1 << 0) -#define B100_FLAG_TX_CTRL_POLICY_NEXT_PACKET   (0x1 << 1) -#define B100_FLAG_TX_CTRL_POLICY_NEXT_BURST    (0x1 << 2) - -///////////////////////////////////////////////// -// TX FE -//////////////////////////////////////////////// -#define B100_REG_TX_FE_DC_OFFSET_I         B100_REG_SR_ADDR(B100_SR_TX_FRONT + 0) //24 bits -#define B100_REG_TX_FE_DC_OFFSET_Q         B100_REG_SR_ADDR(B100_SR_TX_FRONT + 1) //24 bits -#define B100_REG_TX_FE_MAC_CORRECTION      B100_REG_SR_ADDR(B100_SR_TX_FRONT + 2) //18 bits -#define B100_REG_TX_FE_PHASE_CORRECTION    B100_REG_SR_ADDR(B100_SR_TX_FRONT + 3) //18 bits -#define B100_REG_TX_FE_MUX                 B100_REG_SR_ADDR(B100_SR_TX_FRONT + 4) //8 bits (std output = 0x10, reversed = 0x01) - -///////////////////////////////////////////////// -// VITA49 64 bit time (write only) -//////////////////////////////////////////////// -#define B100_REG_TIME64_SECS      B100_REG_SR_ADDR(B100_SR_TIME64 + 0) -#define B100_REG_TIME64_TICKS     B100_REG_SR_ADDR(B100_SR_TIME64 + 1) -#define B100_REG_TIME64_FLAGS     B100_REG_SR_ADDR(B100_SR_TIME64 + 2) -#define B100_REG_TIME64_IMM       B100_REG_SR_ADDR(B100_SR_TIME64 + 3) -#define B100_REG_TIME64_TPS       B100_REG_SR_ADDR(B100_SR_TIME64 + 4) -#define B100_REG_TIME64_MIMO_SYNC B100_REG_SR_ADDR(B100_SR_TIME64 + 5) - -//pps flags (see above) -#define B100_FLAG_TIME64_PPS_NEGEDGE (0 << 0) -#define B100_FLAG_TIME64_PPS_POSEDGE (1 << 0) -#define B100_FLAG_TIME64_PPS_SMA     (0 << 1) -#define B100_FLAG_TIME64_PPS_MIMO    (1 << 1) - -#define B100_FLAG_TIME64_LATCH_NOW 1 -#define B100_FLAG_TIME64_LATCH_NEXT_PPS 0 -  #endif diff --git a/host/lib/usrp/b100/clock_ctrl.cpp b/host/lib/usrp/b100/clock_ctrl.cpp index 02091f00a..c93ff64c7 100644 --- a/host/lib/usrp/b100/clock_ctrl.cpp +++ b/host/lib/usrp/b100/clock_ctrl.cpp @@ -169,11 +169,17 @@ 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; +        //perform soft-reset +        _ad9522_regs.soft_reset = 1; +        this->send_reg(0x000); +        this->latch_regs(); +        _ad9522_regs.soft_reset = 0; +          //init the clock gen registers          _ad9522_regs.sdo_active = ad9522_regs_t::SDO_ACTIVE_SDO_SDIO;          _ad9522_regs.enb_stat_eeprom_at_stat_pin = 0; //use status pin @@ -294,7 +300,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 +433,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 +452,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 +525,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/codec_impl.cpp b/host/lib/usrp/b100/codec_impl.cpp deleted file mode 100644 index a959c9d60..000000000 --- a/host/lib/usrp/b100/codec_impl.cpp +++ /dev/null @@ -1,149 +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_impl.hpp" -#include <uhd/exception.hpp> -#include <uhd/usrp/codec_props.hpp> -#include <boost/bind.hpp> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * Helper Methods - **********************************************************************/ -void b100_impl::codec_init(void){ -    //make proxies -    _rx_codec_proxy = wax_obj_proxy::make( -        boost::bind(&b100_impl::rx_codec_get, this, _1, _2), -        boost::bind(&b100_impl::rx_codec_set, this, _1, _2) -    ); -    _tx_codec_proxy = wax_obj_proxy::make( -        boost::bind(&b100_impl::tx_codec_get, this, _1, _2), -        boost::bind(&b100_impl::tx_codec_set, this, _1, _2) -    ); -} - -/*********************************************************************** - * RX Codec Properties - **********************************************************************/ -static const std::string ad9862_pga_gain_name = "ad9862 pga"; - -void b100_impl::rx_codec_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_NAME: -        val = std::string("b100 adc - ad9522"); -        return; - -    case CODEC_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case CODEC_PROP_GAIN_NAMES: -        val = prop_names_t(1, ad9862_pga_gain_name); -        return; - -    case CODEC_PROP_GAIN_RANGE: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        val = b100_codec_ctrl::rx_pga_gain_range; -        return; - -    case CODEC_PROP_GAIN_I: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        val = _codec_ctrl->get_rx_pga_gain('A'); -        return; - -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        val = _codec_ctrl->get_rx_pga_gain('B'); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void b100_impl::rx_codec_set(const wax::obj &key_, const wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the set request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_GAIN_I: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        _codec_ctrl->set_rx_pga_gain(val.as<double>(), 'A'); -        return; - -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        _codec_ctrl->set_rx_pga_gain(val.as<double>(), 'B'); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} - -/*********************************************************************** - * TX Codec Properties - **********************************************************************/ -void b100_impl::tx_codec_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_NAME: -        val = std::string("b100 dac - ad9522"); -        return; - -    case CODEC_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case CODEC_PROP_GAIN_NAMES: -        val = prop_names_t(1, ad9862_pga_gain_name); -        return; - -    case CODEC_PROP_GAIN_RANGE: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        val = b100_codec_ctrl::tx_pga_gain_range; -        return; - -    case CODEC_PROP_GAIN_I: //only one gain for I and Q -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        val = _codec_ctrl->get_tx_pga_gain(); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void b100_impl::tx_codec_set(const wax::obj &key_, const wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the set request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_GAIN_I: //only one gain for I and Q -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        _codec_ctrl->set_tx_pga_gain(val.as<double>()); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} 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/dboard_impl.cpp b/host/lib/usrp/b100/dboard_impl.cpp deleted file mode 100644 index ed1d4bb1d..000000000 --- a/host/lib/usrp/b100/dboard_impl.cpp +++ /dev/null @@ -1,185 +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_impl.hpp" -#include "b100_regs.hpp" -#include <uhd/exception.hpp> -#include <uhd/usrp/dboard_props.hpp> -#include <uhd/usrp/subdev_props.hpp> -#include <uhd/usrp/misc_utils.hpp> -#include <boost/bind.hpp> -#include "usrp_i2c_addr.h" - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * Dboard Initialization - **********************************************************************/ -void b100_impl::dboard_init(void){ -    //read the tx and rx dboard eeproms -    _rx_db_eeprom.load(*_iface, I2C_ADDR_RX_A); -    _tx_db_eeprom.load(*_iface, I2C_ADDR_TX_A); -    _gdb_eeprom.load(*_iface, I2C_ADDR_TX_A ^ 5); - -    //create a new dboard interface and manager -    _dboard_iface = make_b100_dboard_iface( -        _iface, _clock_ctrl, _codec_ctrl -    ); -    _dboard_manager = dboard_manager::make( -        _rx_db_eeprom.id, -        ((_gdb_eeprom.id == dboard_id_t::none())? _tx_db_eeprom : _gdb_eeprom).id, -        _dboard_iface -    ); - -    //setup the dboard proxies -    _rx_dboard_proxy = wax_obj_proxy::make( -        boost::bind(&b100_impl::rx_dboard_get, this, _1, _2), -        boost::bind(&b100_impl::rx_dboard_set, this, _1, _2) -    ); -    _tx_dboard_proxy = wax_obj_proxy::make( -        boost::bind(&b100_impl::tx_dboard_get, this, _1, _2), -        boost::bind(&b100_impl::tx_dboard_set, this, _1, _2) -    ); -} - -/*********************************************************************** - * RX Dboard Get - **********************************************************************/ -void b100_impl::rx_dboard_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_NAME: -        val = std::string("b100 dboard (rx unit)"); -        return; - -    case DBOARD_PROP_SUBDEV: -        val = _dboard_manager->get_rx_subdev(key.name); -        return; - -    case DBOARD_PROP_SUBDEV_NAMES: -        val = _dboard_manager->get_rx_subdev_names(); -        return; - -    case DBOARD_PROP_DBOARD_EEPROM: -        val = _rx_db_eeprom; -        return; - -    case DBOARD_PROP_DBOARD_IFACE: -        val = _dboard_iface; -        return; - -    case DBOARD_PROP_CODEC: -        val = _rx_codec_proxy->get_link(); -        return; - -    case DBOARD_PROP_GAIN_GROUP: -        val = make_gain_group( -            _rx_db_eeprom.id, -            _dboard_manager->get_rx_subdev(key.name), -            _rx_codec_proxy->get_link(), -            GAIN_GROUP_POLICY_RX -        ); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * RX Dboard Set - **********************************************************************/ -void b100_impl::rx_dboard_set(const wax::obj &key, const wax::obj &val){ -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_DBOARD_EEPROM: -        _rx_db_eeprom = val.as<dboard_eeprom_t>(); -        _rx_db_eeprom.store(*_iface, I2C_ADDR_RX_A); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} - -/*********************************************************************** - * TX Dboard Get - **********************************************************************/ -void b100_impl::tx_dboard_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_NAME: -        val = std::string("b100 dboard (tx unit)"); -        return; - -    case DBOARD_PROP_SUBDEV: -        val = _dboard_manager->get_tx_subdev(key.name); -        return; - -    case DBOARD_PROP_SUBDEV_NAMES: -        val = _dboard_manager->get_tx_subdev_names(); -        return; - -    case DBOARD_PROP_DBOARD_EEPROM: -        val = _tx_db_eeprom; -        return; - -    case DBOARD_PROP_GBOARD_EEPROM: -        val = _gdb_eeprom; -        return; - -    case DBOARD_PROP_DBOARD_IFACE: -        val = _dboard_iface; -        return; - -    case DBOARD_PROP_CODEC: -        val = _tx_codec_proxy->get_link(); -        return; - -    case DBOARD_PROP_GAIN_GROUP: -        val = make_gain_group( -            _tx_db_eeprom.id, -            _dboard_manager->get_tx_subdev(key.name), -            _tx_codec_proxy->get_link(), -            GAIN_GROUP_POLICY_TX -        ); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * TX Dboard Set - **********************************************************************/ -void b100_impl::tx_dboard_set(const wax::obj &key, const wax::obj &val){ -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_DBOARD_EEPROM: -        _tx_db_eeprom = val.as<dboard_eeprom_t>(); -        _tx_db_eeprom.store(*_iface, I2C_ADDR_TX_A); -        return; - -    case DBOARD_PROP_GBOARD_EEPROM: -        _gdb_eeprom = val.as<dboard_eeprom_t>(); -        _gdb_eeprom.store(*_iface, I2C_ADDR_TX_A ^ 5); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/b100/dsp_impl.cpp b/host/lib/usrp/b100/dsp_impl.cpp deleted file mode 100644 index e27894c1a..000000000 --- a/host/lib/usrp/b100/dsp_impl.cpp +++ /dev/null @@ -1,217 +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_impl.hpp" -#include "b100_regs.hpp" -#include <uhd/usrp/dsp_utils.hpp> -#include <uhd/usrp/dsp_props.hpp> -#include <boost/math/special_functions/round.hpp> -#include <boost/bind.hpp> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * DSP impl and methods - **********************************************************************/ -struct b100_impl::dsp_impl{ -    uhd::dict<size_t, size_t> ddc_decim; -    uhd::dict<size_t, double> ddc_freq; -    uhd::dict<size_t, size_t> duc_interp; -    uhd::dict<size_t, double> duc_freq; -}; - -/*********************************************************************** - * RX DDC Initialization - **********************************************************************/ -void b100_impl::dsp_init(void){ -    //create new dsp impl -    _dsp_impl = UHD_PIMPL_MAKE(dsp_impl, ()); - -    //bind and initialize the rx dsps -    for (size_t i = 0; i < B100_NUM_RX_DSPS; i++){ -        _rx_dsp_proxies[str(boost::format("DSP%d")%i)] = wax_obj_proxy::make( -            boost::bind(&b100_impl::ddc_get, this, _1, _2, i), -            boost::bind(&b100_impl::ddc_set, this, _1, _2, i) -        ); - -        //initial config and update -        ddc_set(DSP_PROP_FREQ_SHIFT, double(0), i); -        ddc_set(DSP_PROP_HOST_RATE, double(_clock_ctrl->get_fpga_clock_rate()/16), i); - -        //setup the rx control registers -        _iface->poke32(B100_REG_RX_CTRL_CLEAR(i), 1); //reset -        _iface->poke32(B100_REG_RX_CTRL_NSAMPS_PP(i), this->get_max_recv_samps_per_packet()); -        _iface->poke32(B100_REG_RX_CTRL_NCHANNELS(i), 1); -        _iface->poke32(B100_REG_RX_CTRL_VRT_HDR(i), 0 -            | (0x1 << 28) //if data with stream id -            | (0x1 << 26) //has trailer -            | (0x3 << 22) //integer time other -            | (0x1 << 20) //fractional time sample count -        ); -        _iface->poke32(B100_REG_RX_CTRL_VRT_SID(i), B100_DSP_SID_BASE + i); -        _iface->poke32(B100_REG_RX_CTRL_VRT_TLR(i), 0); -        _iface->poke32(B100_REG_TIME64_TPS, size_t(_clock_ctrl->get_fpga_clock_rate())); -    } - -    //bind and initialize the tx dsps -    for (size_t i = 0; i < B100_NUM_TX_DSPS; i++){ -        _tx_dsp_proxies[str(boost::format("DSP%d")%i)] = wax_obj_proxy::make( -            boost::bind(&b100_impl::duc_get, this, _1, _2, i), -            boost::bind(&b100_impl::duc_set, this, _1, _2, i) -        ); - -        //initial config and update -        duc_set(DSP_PROP_FREQ_SHIFT, double(0), i); -        duc_set(DSP_PROP_HOST_RATE, double(_clock_ctrl->get_fpga_clock_rate()/16), i); - -        //init the tx control registers -        _iface->poke32(B100_REG_TX_CTRL_CLEAR_STATE, 1); //reset -        _iface->poke32(B100_REG_TX_CTRL_NUM_CHAN, 0);    //1 channel -        _iface->poke32(B100_REG_TX_CTRL_REPORT_SID, B100_ASYNC_SID); -        _iface->poke32(B100_REG_TX_CTRL_POLICY, B100_FLAG_TX_CTRL_POLICY_NEXT_PACKET); -    } -} - -/*********************************************************************** - * RX DDC Get - **********************************************************************/ -void b100_impl::ddc_get(const wax::obj &key_, wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ -    case DSP_PROP_NAME: -        val = str(boost::format("%s ddc%d") % _iface->get_cname() % which_dsp); -        return; - -    case DSP_PROP_OTHERS: -        val = prop_names_t(); //empty -        return; - -    case DSP_PROP_FREQ_SHIFT: -        val = _dsp_impl->ddc_freq[which_dsp]; -        return; - -    case DSP_PROP_CODEC_RATE: -        val = _clock_ctrl->get_fpga_clock_rate(); -        return; - -    case DSP_PROP_HOST_RATE: -        val = _clock_ctrl->get_fpga_clock_rate()/_dsp_impl->ddc_decim[which_dsp]; -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * RX DDC Set - **********************************************************************/ -void b100_impl::ddc_set(const wax::obj &key_, const wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ - -    case DSP_PROP_STREAM_CMD: -        issue_ddc_stream_cmd(val.as<stream_cmd_t>(), which_dsp); -        return; - -    case DSP_PROP_FREQ_SHIFT:{ -            double new_freq = val.as<double>(); -            _iface->poke32(B100_REG_DSP_RX_FREQ(which_dsp), -                dsp_type1::calc_cordic_word_and_update(new_freq, _clock_ctrl->get_fpga_clock_rate()) -            ); -            _dsp_impl->ddc_freq[which_dsp] = new_freq; //shadow -        } -        return; - -    case DSP_PROP_HOST_RATE:{ -            _dsp_impl->ddc_decim[which_dsp] = boost::math::iround(_clock_ctrl->get_fpga_clock_rate()/val.as<double>()); - -            //set the decimation -            _iface->poke32(B100_REG_DSP_RX_DECIM(which_dsp), dsp_type1::calc_cic_filter_word(_dsp_impl->ddc_decim[which_dsp])); -        } -        this->update_xport_channel_mapping(); //rate changed -> update -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} - -/*********************************************************************** - * TX DUC Get - **********************************************************************/ -void b100_impl::duc_get(const wax::obj &key_, wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ -    case DSP_PROP_NAME: -        val = str(boost::format("%s duc%d") % _iface->get_cname() % which_dsp); -        return; - -    case DSP_PROP_OTHERS: -        val = prop_names_t(); //empty -        return; - -    case DSP_PROP_FREQ_SHIFT: -        val = _dsp_impl->duc_freq[which_dsp]; -        return; - -    case DSP_PROP_CODEC_RATE: -        val = _clock_ctrl->get_fpga_clock_rate(); -        return; - -    case DSP_PROP_HOST_RATE: -        val = _clock_ctrl->get_fpga_clock_rate()/_dsp_impl->duc_interp[which_dsp]; -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * TX DUC Set - **********************************************************************/ -void b100_impl::duc_set(const wax::obj &key_, const wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ - -    case DSP_PROP_FREQ_SHIFT:{ -            double new_freq = val.as<double>(); -            _iface->poke32(B100_REG_DSP_TX_FREQ, -                dsp_type1::calc_cordic_word_and_update(new_freq, _clock_ctrl->get_fpga_clock_rate()) -            ); -            _dsp_impl->duc_freq[which_dsp] = new_freq; //shadow -        } -        return; - -    case DSP_PROP_HOST_RATE:{ -            _dsp_impl->duc_interp[which_dsp] = boost::math::iround(_clock_ctrl->get_fpga_clock_rate()/val.as<double>()); - -            //set the interpolation -            _iface->poke32(B100_REG_DSP_TX_INTERP_RATE, dsp_type1::calc_cic_filter_word(_dsp_impl->duc_interp[which_dsp])); - -            //set the scaling -            _iface->poke32(B100_REG_DSP_TX_SCALE_IQ, dsp_type1::calc_iq_scale_word(_dsp_impl->duc_interp[which_dsp])); -        } -        this->update_xport_channel_mapping(); //rate changed -> update -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/b100/io_impl.cpp b/host/lib/usrp/b100/io_impl.cpp index 5377c43d5..d4515bbb5 100644 --- a/host/lib/usrp/b100/io_impl.cpp +++ b/host/lib/usrp/b100/io_impl.cpp @@ -15,133 +15,190 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // +#include "recv_packet_demuxer.hpp" +#include "validate_subdev_spec.hpp"  #include "../../transport/super_recv_packet_handler.hpp"  #include "../../transport/super_send_packet_handler.hpp"  #include "usrp_commands.h"  #include "b100_impl.hpp"  #include "b100_regs.hpp" -#include <uhd/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>  #include <boost/format.hpp> -#include <boost/asio.hpp>  #include <boost/bind.hpp>  #include <boost/thread.hpp>  #include <uhd/utils/msg.hpp>  #include <uhd/utils/log.hpp> -#include <iostream>  using namespace uhd;  using namespace uhd::usrp;  using namespace uhd::transport; -namespace asio = boost::asio;  /***********************************************************************   * IO Implementation Details   **********************************************************************/  struct b100_impl::io_impl{ -    io_impl(zero_copy_if::sptr data_transport): -        data_transport(data_transport) -    { -        for (size_t i = 0; i < B100_NUM_RX_DSPS; 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())); -        } -    } - -    ~io_impl(void){ -        for (size_t i = 0; i < _buffs_queue.size(); i++){ -            delete _buffs_queue[i]; -        } -    } +    io_impl(void): +        async_msg_fifo(100/*messages deep*/) +    { /* NOP */ }      zero_copy_if::sptr data_transport; - -    std::vector<bounded_buffer<managed_recv_buffer::sptr> *> _buffs_queue; - -    //gets buffer, determines if its the requested index, -    //and either queues the buffer or returns the buffer -    managed_recv_buffer::sptr get_recv_buff(const size_t index, const double timeout){ -        while (true){ -            managed_recv_buffer::sptr buff; - -            //attempt to pop a buffer from the queue -            if (_buffs_queue[index]->pop_with_haste(buff)) return buff; - -            //otherwise, call into the transport -            buff = data_transport->get_recv_buff(timeout); -            if (buff.get() == NULL) return buff; //timeout - -            //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; -            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); -            else UHD_MSG(error) << "Got a data packet with known SID " << uhd::wtohx(vrt_hdr[1]) << std::endl; -        } -    } - +    bounded_buffer<async_metadata_t> async_msg_fifo; +    recv_packet_demuxer::sptr demuxer;      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_LITTLE_ENDIAN; + +    //setup tx otw type +    _tx_otw_type.width = 16; +    _tx_otw_type.shift = 0; +    _tx_otw_type.byteorder = uhd::otw_type_t::BO_LITTLE_ENDIAN; + +    //TODO best place to put this? +    this->reset_gpif(6);      //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, ()); +    _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)); -    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 +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; +        metadata.channel = 0; +        metadata.has_time_spec = if_packet_info.has_tsi and if_packet_info.has_tsf; +        metadata.time_spec = time_spec_t( +            time_t(if_packet_info.tsi), size_t(if_packet_info.tsf), _clock_ctrl->get_fpga_clock_rate() +        ); +        metadata.event_code = async_metadata_t::event_code_t(sph::get_context_code(vrt_hdr, if_packet_info)); +        _io_impl->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_IN_PACKET) +        ) UHD_MSG(fastpath) << "U"; +        else if (metadata.event_code & +            ( async_metadata_t::EVENT_CODE_SEQ_ERROR +            | async_metadata_t::EVENT_CODE_SEQ_ERROR_IN_BURST) +        ) UHD_MSG(fastpath) << "S"; +    } +    else UHD_MSG(error) << "Unknown async packet" << std::endl; +} -    //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 +    validate_subdev_spec(_tree, spec, "rx"); + +    //setup mux for this spec +    bool fe_swapped = false; +    for (size_t i = 0; i < spec.size(); i++){ +        const std::string conn = _tree->access<std::string>(root / spec[i].db_name / "rx_frontends" / spec[i].sd_name / "connection").get(); +        if (i == 0 and (conn == "QI" or conn == "Q")) fe_swapped = true; +        _rx_dsps[i]->set_mux(conn, fe_swapped); +    } +    _rx_fe->set_mux(fe_swapped); + +    //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( +            &recv_packet_demuxer::get_recv_buff, _io_impl->demuxer, 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 +    validate_subdev_spec(_tree, spec, "tx"); + +    //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->send_handler.set_xport_chan_get_buff(i, boost::bind( +            &zero_copy_if::get_send_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( +    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); +} + +/*********************************************************************** + * Send Data   **********************************************************************/  size_t b100_impl::get_max_send_samps_per_packet(void) const {      static const size_t hdr_size = 0 @@ -149,7 +206,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 +222,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 +231,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 +245,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/b100/mboard_impl.cpp b/host/lib/usrp/b100/mboard_impl.cpp deleted file mode 100644 index 4f7dc8fce..000000000 --- a/host/lib/usrp/b100/mboard_impl.cpp +++ /dev/null @@ -1,282 +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_impl.hpp" -#include "usrp_commands.h" -#include "fpga_regs_standard.h" -#include "fpga_regs_common.h" -#include "b100_regs.hpp" -#include "usrp_i2c_addr.h" -#include <uhd/usrp/misc_utils.hpp> -#include <uhd/usrp/mboard_props.hpp> -#include <uhd/usrp/dboard_props.hpp> -#include <uhd/usrp/subdev_props.hpp> -#include <uhd/utils/msg.hpp> -#include <uhd/exception.hpp> -#include <uhd/utils/images.hpp> -#include <boost/assign/list_of.hpp> -#include <boost/foreach.hpp> -#include <boost/bind.hpp> -#include <boost/thread/thread.hpp> -#include <uhd/usrp/dsp_utils.hpp> - -using namespace uhd; -using namespace uhd::usrp; - -static const bool b100_mboard_verbose = true; - -/*********************************************************************** - * Mboard Initialization - **********************************************************************/ -void b100_impl::mboard_init(void) -{ -    _mboard_proxy = wax_obj_proxy::make( -                     boost::bind(&b100_impl::mboard_get, this, _1, _2), -                     boost::bind(&b100_impl::mboard_set, this, _1, _2)); - -    //set the ticks per seconds into the vita time control -    _iface->poke32(B100_REG_TIME64_TPS, -        boost::uint32_t(_clock_ctrl->get_fpga_clock_rate()) -    ); -     -    //init the clock config -    _clock_config = clock_config_t::internal(); -    update_clock_config(); -} - -void b100_impl::update_clock_config(void){ -    boost::uint32_t pps_flags = 0; - -    //translate pps polarity enums -    switch(_clock_config.pps_polarity){ -    case clock_config_t::PPS_POS: pps_flags |= B100_FLAG_TIME64_PPS_POSEDGE; break; -    case clock_config_t::PPS_NEG: pps_flags |= B100_FLAG_TIME64_PPS_NEGEDGE; break; -    default: throw uhd::runtime_error("unhandled clock configuration pps polarity"); -    } - -    //set the pps flags -    _iface->poke32(B100_REG_TIME64_FLAGS, pps_flags); - -    //clock source ref 10mhz -    switch(_clock_config.ref_source){ -    case clock_config_t::REF_AUTO: _clock_ctrl->use_auto_ref(); break; -    case clock_config_t::REF_INT: _clock_ctrl->use_internal_ref(); break; -    case clock_config_t::REF_SMA: _clock_ctrl->use_auto_ref(); break; -    default: throw uhd::runtime_error("unhandled clock configuration ref source"); -    } -} - -/*********************************************************************** - * Mboard Get - **********************************************************************/ -void b100_impl::mboard_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); -    static const std::string dboard_name = "A"; - -    //handle the get request conditioned on the key -    switch(key.as<mboard_prop_t>()){ -    case MBOARD_PROP_NAME: -        val = std::string(_iface->get_cname() + " mboard"); -        return; - -    case MBOARD_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case MBOARD_PROP_RX_DBOARD: -        UHD_ASSERT_THROW(key.name == dboard_name); -        val = _rx_dboard_proxy->get_link(); -        return; - -    case MBOARD_PROP_RX_DBOARD_NAMES: -        val = prop_names_t(1, dboard_name); -        return; - -    case MBOARD_PROP_TX_DBOARD: -        UHD_ASSERT_THROW(key.name == dboard_name); -        val = _tx_dboard_proxy->get_link(); -        return; - -    case MBOARD_PROP_TX_DBOARD_NAMES: -        val = prop_names_t(1, dboard_name); -        return; - -    case MBOARD_PROP_RX_DSP: -        val = _rx_dsp_proxies[key.name]->get_link(); -        return; - -    case MBOARD_PROP_RX_DSP_NAMES: -        val = _rx_dsp_proxies.keys(); -        return; - -    case MBOARD_PROP_TX_DSP: -        val = _tx_dsp_proxies[key.name]->get_link(); -        return; - -    case MBOARD_PROP_TX_DSP_NAMES: -        val = _tx_dsp_proxies.keys(); -        return; - -    case MBOARD_PROP_CLOCK_CONFIG: -        val = _clock_config; -        return; - -    case MBOARD_PROP_RX_SUBDEV_SPEC: -        val = _rx_subdev_spec; -        return; - -    case MBOARD_PROP_TX_SUBDEV_SPEC: -        val = _tx_subdev_spec; -        return; -         -    case MBOARD_PROP_EEPROM_MAP: -        val = _iface->mb_eeprom; -        return; - -    case MBOARD_PROP_TIME_NOW:while(true){ -        uint32_t secs = _iface->peek32(B100_REG_RB_TIME_NOW_SECS); -        uint32_t ticks = _iface->peek32(B100_REG_RB_TIME_NOW_TICKS); -        if (secs != _iface->peek32(B100_REG_RB_TIME_NOW_SECS)) continue; -        val = time_spec_t(secs, ticks, _clock_ctrl->get_fpga_clock_rate()); -        return; -    } -     -    case MBOARD_PROP_TIME_PPS: while(true){ -        uint32_t secs = _iface->peek32(B100_REG_RB_TIME_PPS_SECS); -        uint32_t ticks = _iface->peek32(B100_REG_RB_TIME_PPS_TICKS); -        if (secs != _iface->peek32(B100_REG_RB_TIME_PPS_SECS)) continue; -        val = time_spec_t(secs, ticks, _clock_ctrl->get_fpga_clock_rate()); -        return; -    } - -    case MBOARD_PROP_CLOCK_RATE: -        val = _clock_ctrl->get_fpga_clock_rate(); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * Mboard Set - **********************************************************************/ -void b100_impl::mboard_set(const wax::obj &key, const wax::obj &val) -{ -    if(key.type() == typeid(std::string)) { -      if(key.as<std::string>() == "load_eeprom") { -        std::string b100_eeprom_image = val.as<std::string>(); -        UHD_MSG(status) << "B100 EEPROM image: " << b100_eeprom_image << std::endl; -        _fx2_ctrl->usrp_load_eeprom(val.as<std::string>()); -      } -      return; -   	} - -    //handle the get request conditioned on the key -    switch(key.as<mboard_prop_t>()){ -    case MBOARD_PROP_TIME_NOW: -    case MBOARD_PROP_TIME_PPS:{ -            time_spec_t time_spec = val.as<time_spec_t>(); -            _iface->poke32(B100_REG_TIME64_TICKS, time_spec.get_tick_count(_clock_ctrl->get_fpga_clock_rate())); -            boost::uint32_t imm_flags = (key.as<mboard_prop_t>() == MBOARD_PROP_TIME_NOW)? 1 : 0; -            _iface->poke32(B100_REG_TIME64_IMM, imm_flags); -            _iface->poke32(B100_REG_TIME64_SECS, boost::uint32_t(time_spec.get_full_secs())); -        } -        return; - -    case MBOARD_PROP_RX_SUBDEV_SPEC:{ -        _rx_subdev_spec = val.as<subdev_spec_t>(); -        verify_rx_subdev_spec(_rx_subdev_spec, _mboard_proxy->get_link()); -        //sanity check -        UHD_ASSERT_THROW(_rx_subdev_spec.size() <= B100_NUM_RX_DSPS); - -        //determine frontend swap IQ from the first channel -        bool fe_swap_iq = false; -        switch(_dboard_manager->get_rx_subdev(_rx_subdev_spec.at(0).sd_name)[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>()){ -        case SUBDEV_CONN_COMPLEX_QI: -        case SUBDEV_CONN_REAL_Q: -            fe_swap_iq = true; -            break; -        default: fe_swap_iq = false; -        } -        _iface->poke32(B100_REG_RX_FE_SWAP_IQ, fe_swap_iq? 1 : 0); - -        //set the dsp mux for each channel -        for (size_t i = 0; i < _rx_subdev_spec.size(); i++){ -            bool iq_swap = false, real_mode = false; -            switch(_dboard_manager->get_rx_subdev(_rx_subdev_spec.at(i).sd_name)[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>()){ -            case SUBDEV_CONN_COMPLEX_IQ: -                iq_swap = fe_swap_iq; -                real_mode = false; -                break; -            case SUBDEV_CONN_COMPLEX_QI: -                iq_swap = not fe_swap_iq; -                real_mode = false; -                break; -            case SUBDEV_CONN_REAL_I: -                iq_swap = fe_swap_iq; -                real_mode = true; -                break; -            case SUBDEV_CONN_REAL_Q: -                iq_swap = not fe_swap_iq; -                real_mode = true; -                break; -            } -            _iface->poke32(B100_REG_DSP_RX_MUX(i), -                (iq_swap?   B100_FLAG_DSP_RX_MUX_SWAP_IQ   : 0) | -                (real_mode? B100_FLAG_DSP_RX_MUX_REAL_MODE : 0) -            ); -        } -        this->update_xport_channel_mapping(); -    }return; - -    case MBOARD_PROP_TX_SUBDEV_SPEC: -        _tx_subdev_spec = val.as<subdev_spec_t>(); -        verify_tx_subdev_spec(_tx_subdev_spec, _mboard_proxy->get_link()); -        //sanity check -        UHD_ASSERT_THROW(_tx_subdev_spec.size() <= B100_NUM_TX_DSPS); -        //set the mux -        _iface->poke32(B100_REG_TX_FE_MUX, dsp_type1::calc_tx_mux_word( -            _dboard_manager->get_tx_subdev(_tx_subdev_spec.front().sd_name)[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>() -        )); -        return; - -    case MBOARD_PROP_EEPROM_MAP: -        // Step1: commit the map, writing only those values set. -        // Step2: readback the entire eeprom map into the iface. -        val.as<mboard_eeprom_t>().commit(*_iface, mboard_eeprom_t::MAP_B000); -        _iface->mb_eeprom = mboard_eeprom_t(*_iface, mboard_eeprom_t::MAP_B000); -        return; - -    case MBOARD_PROP_CLOCK_CONFIG: -        _clock_config = val.as<clock_config_t>(); -        update_clock_config(); -        return; - -    case MBOARD_PROP_CLOCK_RATE: -        UHD_MSG(warning) -            << "You are setting the master clock rate from the API.\n" -            << "You may want to pass this into the device address as master_clock_rate=<rate>.\n" -            << "This way, the clock rate is guaranteed to be initialized first.\n" -            << "See the application notes for USRP-B100 for further instructions.\n" -        ; -        _clock_ctrl->set_fpga_clock_rate(val.as<double>()); -        update_xport_channel_mapping(); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/fx2/CMakeLists.txt b/host/lib/usrp/common/CMakeLists.txt index 9d1e15e16..ec8b60fec 100644 --- a/host/lib/usrp/fx2/CMakeLists.txt +++ b/host/lib/usrp/common/CMakeLists.txt @@ -16,11 +16,19 @@  #  ######################################################################## +# This file included, use CMake directory variables +########################################################################  IF(ENABLE_USB)      INCLUDE_DIRECTORIES(${CMAKE_SOURCE_DIR}/../firmware/fx2/common)      LIBUHD_APPEND_SOURCES(          ${CMAKE_CURRENT_SOURCE_DIR}/fx2_ctrl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/fx2_ctrl.hpp      )  ENDIF(ENABLE_USB) + +INCLUDE_DIRECTORIES(${CMAKE_CURRENT_SOURCE_DIR}) + +LIBUHD_APPEND_SOURCES( +    ${CMAKE_CURRENT_SOURCE_DIR}/validate_subdev_spec.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/recv_packet_demuxer.cpp +) diff --git a/host/lib/usrp/fx2/fx2_ctrl.cpp b/host/lib/usrp/common/fx2_ctrl.cpp index 06ca51c25..66a03f131 100644 --- a/host/lib/usrp/fx2/fx2_ctrl.cpp +++ b/host/lib/usrp/common/fx2_ctrl.cpp @@ -262,6 +262,7 @@ public:      void usrp_load_eeprom(std::string filestring)      { +        if (load_img_msg) UHD_MSG(status) << "Loading EEPROM image: " << filestring << "..." << std::flush;          const char *filename = filestring.c_str();          const boost::uint16_t i2c_addr = 0x50; @@ -299,6 +300,7 @@ public:              boost::this_thread::sleep(boost::posix_time::milliseconds(100));          }          file.close(); +        if (load_img_msg) UHD_MSG(status) << " done" << std::endl;      } @@ -409,6 +411,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/common/fx2_ctrl.hpp index 37fa09605..691d64275 100644 --- a/host/lib/usrp/fx2/fx2_ctrl.hpp +++ b/host/lib/usrp/common/fx2_ctrl.hpp @@ -15,16 +15,17 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#ifndef INCLUDED_USRP_CTRL_HPP -#define INCLUDED_USRP_CTRL_HPP +#ifndef INCLUDED_LIBUHD_USRP_COMMON_FX2_CTRL_HPP +#define INCLUDED_LIBUHD_USRP_COMMON_FX2_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; @@ -119,4 +120,4 @@ public:  }} //namespace uhd::usrp -#endif /* INCLUDED_USRP_CTRL_HPP */ +#endif /* INCLUDED_LIBUHD_USRP_COMMON_FX2_CTRL_HPP */ diff --git a/host/lib/usrp/common/recv_packet_demuxer.cpp b/host/lib/usrp/common/recv_packet_demuxer.cpp new file mode 100644 index 000000000..93f423aeb --- /dev/null +++ b/host/lib/usrp/common/recv_packet_demuxer.cpp @@ -0,0 +1,87 @@ +// +// 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 "recv_packet_demuxer.hpp" +#include <uhd/utils/msg.hpp> +#include <uhd/utils/byteswap.hpp> +#include <boost/thread/mutex.hpp> +#include <queue> +#include <deque> +#include <vector> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; + +static UHD_INLINE boost::uint32_t extract_sid(managed_recv_buffer::sptr &buff){ +    //ASSUME that the data is in little endian format +    return uhd::wtohx(buff->cast<const boost::uint32_t *>()[1]); +} + +class recv_packet_demuxer_impl : public uhd::usrp::recv_packet_demuxer{ +public: +    recv_packet_demuxer_impl( +        transport::zero_copy_if::sptr transport, +        const size_t size, +        const boost::uint32_t sid_base +    ): +        _transport(transport), _sid_base(sid_base), _queues(size) +    { +        /* NOP */ +    } + +    managed_recv_buffer::sptr get_recv_buff(const size_t index, const double timeout){ +        boost::mutex::scoped_lock lock(_mutex); +        managed_recv_buffer::sptr buff; + +        //there is already an entry in the queue, so pop that +        if (not _queues[index].wrapper.empty()){ +            std::swap(buff, _queues[index].wrapper.front()); +            _queues[index].wrapper.pop(); +            return buff; +        } + +        while (true){ +            //otherwise call into the transport +            buff = _transport->get_recv_buff(timeout); +            if (buff.get() == NULL) return buff; //timeout + +            //check the stream id to know which channel +            const size_t rx_index = extract_sid(buff) - _sid_base; +            if (rx_index == index) return buff; //got expected message + +            //otherwise queue and try again +            if (rx_index < _queues.size()) _queues[rx_index].wrapper.push(buff); +            else UHD_MSG(error) << "Got a data packet with known SID " << extract_sid(buff) << std::endl; +        } +    } + +private: +    transport::zero_copy_if::sptr _transport; +    const boost::uint32_t _sid_base; +    boost::mutex _mutex; +    struct channel_guts_type{ +        channel_guts_type(void): wrapper(container){} +        std::deque<managed_recv_buffer::sptr> container; +        std::queue<managed_recv_buffer::sptr> wrapper; +    }; +    std::vector<channel_guts_type> _queues; +}; + +recv_packet_demuxer::sptr recv_packet_demuxer::make(transport::zero_copy_if::sptr transport, const size_t size, const boost::uint32_t sid_base){ +    return sptr(new recv_packet_demuxer_impl(transport, size, sid_base)); +} diff --git a/host/lib/usrp/common/recv_packet_demuxer.hpp b/host/lib/usrp/common/recv_packet_demuxer.hpp new file mode 100644 index 000000000..fde756d27 --- /dev/null +++ b/host/lib/usrp/common/recv_packet_demuxer.hpp @@ -0,0 +1,41 @@ +// +// 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_LIBUHD_USRP_COMMON_RECV_PACKET_DEMUXER_HPP +#define INCLUDED_LIBUHD_USRP_COMMON_RECV_PACKET_DEMUXER_HPP + +#include <uhd/config.hpp> +#include <uhd/transport/zero_copy.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/cstdint.hpp> + +namespace uhd{ namespace usrp{ + +    class recv_packet_demuxer{ +    public: +        typedef boost::shared_ptr<recv_packet_demuxer> sptr; + +        //! Make a new demuxer from a transport and parameters +        static sptr make(transport::zero_copy_if::sptr transport, const size_t size, const boost::uint32_t sid_base); + +        //! Get a buffer at the given index from the transport +        virtual transport::managed_recv_buffer::sptr get_recv_buff(const size_t index, const double timeout) = 0; +    }; + +}} //namespace uhd::usrp + +#endif /* INCLUDED_LIBUHD_USRP_COMMON_RECV_PACKET_DEMUXER_HPP */ diff --git a/host/lib/usrp/common/validate_subdev_spec.cpp b/host/lib/usrp/common/validate_subdev_spec.cpp new file mode 100644 index 000000000..fab40b204 --- /dev/null +++ b/host/lib/usrp/common/validate_subdev_spec.cpp @@ -0,0 +1,73 @@ +// +// 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 "validate_subdev_spec.hpp" +#include <uhd/exception.hpp> +#include <uhd/utils/assert_has.hpp> +#include <boost/foreach.hpp> +#include <boost/format.hpp> + +using namespace uhd; +using namespace uhd::usrp; + +namespace uhd{ namespace usrp{ + +    static std::ostream& operator<< (std::ostream &out, const subdev_spec_pair_t &pair){ +        out << pair.db_name << ":" << pair.sd_name; +        return out; +    } + +}} + +void uhd::usrp::validate_subdev_spec( +    property_tree::sptr tree, +    const subdev_spec_t &spec, +    const std::string &type, +    const std::string &mb +){ +    const size_t num_dsps = tree->list(str(boost::format("/mboards/%s/%s_dsps") % mb % type)).size(); + +    //sanity checking on the length +    if (spec.size() == 0) throw uhd::value_error(str(boost::format( +        "Empty %s subdevice specification is not supported.\n" +    ) % type)); +    if (spec.size() > num_dsps) throw uhd::value_error(str(boost::format( +        "The subdevice specification \"%s\" is too long.\n" +        "The user specified %u channels, but there are only %u %s dsps on mboard %s.\n" +    ) % spec.to_string() % spec.size() % num_dsps % type % mb)); + +    //make a list of all possible specs +    subdev_spec_t all_specs; +    BOOST_FOREACH(const std::string &db, tree->list(str(boost::format("/mboards/%s/dboards") % mb))){ +        BOOST_FOREACH(const std::string &sd, tree->list(str(boost::format("/mboards/%s/dboards/%s/%s_frontends") % mb % db % type))){ +            all_specs.push_back(subdev_spec_pair_t(db, sd)); +        } +    } + +    //validate that the spec is possible +    BOOST_FOREACH(const subdev_spec_pair_t &pair, spec){ +        uhd::assert_has(all_specs, pair, str(boost::format("%s subdevice specification on mboard %s") % type % mb)); +    } + +    //enable selected frontends, disable others +    BOOST_FOREACH(const subdev_spec_pair_t &pair, all_specs){ +        const bool enb = uhd::has(spec, pair); +        tree->access<bool>(str(boost::format( +            "/mboards/%s/dboards/%s/%s_frontends/%s/enabled" +        ) % mb % pair.db_name % type % pair.sd_name)).set(enb); +    } +} diff --git a/host/lib/usrp/common/validate_subdev_spec.hpp b/host/lib/usrp/common/validate_subdev_spec.hpp new file mode 100644 index 000000000..7d9e2c309 --- /dev/null +++ b/host/lib/usrp/common/validate_subdev_spec.hpp @@ -0,0 +1,38 @@ +// +// 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_LIBUHD_USRP_COMMON_VALIDATE_SUBDEV_SPEC_HPP +#define INCLUDED_LIBUHD_USRP_COMMON_VALIDATE_SUBDEV_SPEC_HPP + +#include <uhd/config.hpp> +#include <uhd/usrp/subdev_spec.hpp> +#include <uhd/property_tree.hpp> +#include <string> + +namespace uhd{ namespace usrp{ + +    //! Validate a subdev spec against a property tree +    void validate_subdev_spec( +        property_tree::sptr tree, +        const subdev_spec_t &spec, +        const std::string &type, //rx or tx +        const std::string &mb = "0" +    ); + +}} //namespace uhd::usrp + +#endif /* INCLUDED_LIBUHD_USRP_COMMON_VALIDATE_SUBDEV_SPEC_HPP */ diff --git a/host/lib/usrp/cores/CMakeLists.txt b/host/lib/usrp/cores/CMakeLists.txt new file mode 100644 index 000000000..4476c9424 --- /dev/null +++ b/host/lib/usrp/cores/CMakeLists.txt @@ -0,0 +1,32 @@ +# +# 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/>. +# + +######################################################################## +# This file included, use CMake directory variables +######################################################################## + +INCLUDE_DIRECTORIES(${CMAKE_CURRENT_SOURCE_DIR}) + +LIBUHD_APPEND_SOURCES( +    ${CMAKE_CURRENT_SOURCE_DIR}/i2c_core_100.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/spi_core_100.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/time64_core_200.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/rx_dsp_core_200.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/tx_dsp_core_200.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/rx_frontend_core_200.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/tx_frontend_core_200.cpp +) diff --git a/host/lib/usrp/cores/i2c_core_100.cpp b/host/lib/usrp/cores/i2c_core_100.cpp new file mode 100644 index 000000000..12352f108 --- /dev/null +++ b/host/lib/usrp/cores/i2c_core_100.cpp @@ -0,0 +1,138 @@ +// +// 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 "i2c_core_100.hpp" +#include <uhd/exception.hpp> +#include <uhd/utils/msg.hpp> +#include <boost/thread/thread.hpp> //sleep + +#define REG_I2C_PRESCALER_LO _base + 0 +#define REG_I2C_PRESCALER_HI _base + 2 +#define REG_I2C_CTRL         _base + 4 +#define REG_I2C_DATA         _base + 6 +#define REG_I2C_CMD_STATUS   _base + 8 + +// +// STA, STO, RD, WR, and IACK bits are cleared automatically +// + +#define	I2C_CTRL_EN	(1 << 7)	// core enable +#define	I2C_CTRL_IE	(1 << 6)	// interrupt enable + +#define	I2C_CMD_START	(1 << 7)	// generate (repeated) start condition +#define I2C_CMD_STOP	(1 << 6)	// generate stop condition +#define	I2C_CMD_RD	(1 << 5)	// read from slave +#define I2C_CMD_WR	(1 << 4)	// write to slave +#define	I2C_CMD_NACK	(1 << 3)	// when a rcvr, send ACK (ACK=0) or NACK (ACK=1) +#define I2C_CMD_RSVD_2	(1 << 2)	// reserved +#define	I2C_CMD_RSVD_1	(1 << 1)	// reserved +#define I2C_CMD_IACK	(1 << 0)	// set to clear pending interrupt + +#define I2C_ST_RXACK	(1 << 7)	// Received acknowledgement from slave (1 = NAK, 0 = ACK) +#define	I2C_ST_BUSY	(1 << 6)	// 1 after START signal detected; 0 after STOP signal detected +#define	I2C_ST_AL	(1 << 5)	// Arbitration lost.  1 when core lost arbitration +#define	I2C_ST_RSVD_4	(1 << 4)	// reserved +#define	I2C_ST_RSVD_3	(1 << 3)	// reserved +#define	I2C_ST_RSVD_2	(1 << 2)	// reserved +#define I2C_ST_TIP	(1 << 1)	// Transfer-in-progress +#define	I2C_ST_IP	(1 << 0)	// Interrupt pending + +using namespace uhd; + +class i2c_core_100_impl : public i2c_core_100{ +public: +    i2c_core_100_impl(wb_iface::sptr iface, const size_t base): +        _iface(iface), _base(base) +    { +        //init I2C FPGA interface. +        _iface->poke16(REG_I2C_CTRL, 0x0000); +        //set prescalers to operate at 400kHz: WB_CLK is 64MHz... +        static const boost::uint32_t i2c_datarate = 400000; +        static const boost::uint32_t wishbone_clk = 64000000; //FIXME should go somewhere else +        boost::uint16_t prescaler = wishbone_clk / (i2c_datarate*5) - 1; +        _iface->poke16(REG_I2C_PRESCALER_LO, prescaler & 0xFF); +        _iface->poke16(REG_I2C_PRESCALER_HI, (prescaler >> 8) & 0xFF); +        _iface->poke16(REG_I2C_CTRL, I2C_CTRL_EN); //enable I2C core +    } + +    void write_i2c( +        boost::uint8_t addr, +        const byte_vector_t &bytes +    ){ +        _iface->poke16(REG_I2C_DATA, (addr << 1) | 0); //addr and read bit (0) +        _iface->poke16(REG_I2C_CMD_STATUS, I2C_CMD_WR | I2C_CMD_START | (bytes.size() == 0 ? I2C_CMD_STOP : 0)); + +        //wait for previous transfer to complete +        if (not wait_chk_ack()) { +            _iface->poke16(REG_I2C_CMD_STATUS, I2C_CMD_STOP); +            return; +        } + +        for (size_t i = 0; i < bytes.size(); i++) { +            _iface->poke16(REG_I2C_DATA, bytes[i]); +            _iface->poke16(REG_I2C_CMD_STATUS, I2C_CMD_WR | ((i == (bytes.size() - 1)) ? I2C_CMD_STOP : 0)); +            if(!wait_chk_ack()) { +                _iface->poke16(REG_I2C_CMD_STATUS, I2C_CMD_STOP); +                return; +            } +        } +    } + +    byte_vector_t read_i2c( +        boost::uint8_t addr, +        size_t num_bytes +    ){ +        byte_vector_t bytes; +        if (num_bytes == 0) return bytes; + +        while (_iface->peek16(REG_I2C_CMD_STATUS) & I2C_ST_BUSY); + +        _iface->poke16(REG_I2C_DATA, (addr << 1) | 1); //addr and read bit (1) +        _iface->poke16(REG_I2C_CMD_STATUS, I2C_CMD_WR | I2C_CMD_START); +        //wait for previous transfer to complete +        if (not wait_chk_ack()) { +            _iface->poke16(REG_I2C_CMD_STATUS, I2C_CMD_STOP); +        } +        for (size_t i = 0; i < num_bytes; i++) { +            _iface->poke16(REG_I2C_CMD_STATUS, I2C_CMD_RD | ((num_bytes == i+1) ? (I2C_CMD_STOP | I2C_CMD_NACK) : 0)); +            i2c_wait(); +            bytes.push_back(boost::uint8_t(_iface->peek16(REG_I2C_DATA))); +        } +        return bytes; +    } + +private: +    void i2c_wait(void) { +        for (size_t i = 0; i < 100; i++){ +            if ((_iface->peek16(REG_I2C_CMD_STATUS) & I2C_ST_TIP) == 0) return; +            boost::this_thread::sleep(boost::posix_time::milliseconds(1)); +        } +        UHD_MSG(error) << "i2c_core_100: i2c_wait timeout" << std::endl; +    } + +    bool wait_chk_ack(void){ +        i2c_wait(); +        return (_iface->peek16(REG_I2C_CMD_STATUS) & I2C_ST_RXACK) == 0; +    } + +    wb_iface::sptr _iface; +    const size_t _base; +}; + +i2c_core_100::sptr i2c_core_100::make(wb_iface::sptr iface, const size_t base){ +    return sptr(new i2c_core_100_impl(iface, base)); +} diff --git a/host/lib/usrp/cores/i2c_core_100.hpp b/host/lib/usrp/cores/i2c_core_100.hpp new file mode 100644 index 000000000..f7a5ae4f7 --- /dev/null +++ b/host/lib/usrp/cores/i2c_core_100.hpp @@ -0,0 +1,35 @@ +// +// 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_LIBUHD_USRP_I2C_CORE_100_HPP +#define INCLUDED_LIBUHD_USRP_I2C_CORE_100_HPP + +#include <uhd/config.hpp> +#include <uhd/types/serial.hpp> +#include <boost/utility.hpp> +#include <boost/shared_ptr.hpp> +#include "wb_iface.hpp" + +class i2c_core_100 : boost::noncopyable, public uhd::i2c_iface{ +public: +    typedef boost::shared_ptr<i2c_core_100> sptr; + +    //! makes a new i2c core from iface and slave base +    static sptr make(wb_iface::sptr iface, const size_t base); +}; + +#endif /* INCLUDED_LIBUHD_USRP_I2C_CORE_100_HPP */ diff --git a/host/lib/usrp/cores/rx_dsp_core_200.cpp b/host/lib/usrp/cores/rx_dsp_core_200.cpp new file mode 100644 index 000000000..e059ddfca --- /dev/null +++ b/host/lib/usrp/cores/rx_dsp_core_200.cpp @@ -0,0 +1,188 @@ +// +// 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 "rx_dsp_core_200.hpp" +#include <uhd/types/dict.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/algorithm.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/math/special_functions/round.hpp> +#include <boost/math/special_functions/sign.hpp> +#include <algorithm> +#include <cmath> + +#define REG_DSP_RX_FREQ       _dsp_base + 0 +//skip one right here +#define REG_DSP_RX_DECIM      _dsp_base + 8 +#define REG_DSP_RX_MUX        _dsp_base + 12 + +#define FLAG_DSP_RX_MUX_SWAP_IQ   (1 << 0) +#define FLAG_DSP_RX_MUX_REAL_MODE (1 << 1) + +#define REG_RX_CTRL_STREAM_CMD     _ctrl_base + 0 +#define REG_RX_CTRL_TIME_SECS      _ctrl_base + 4 +#define REG_RX_CTRL_TIME_TICKS     _ctrl_base + 8 +#define REG_RX_CTRL_CLEAR          _ctrl_base + 12 +#define REG_RX_CTRL_VRT_HDR        _ctrl_base + 16 +#define REG_RX_CTRL_VRT_SID        _ctrl_base + 20 +#define REG_RX_CTRL_VRT_TLR        _ctrl_base + 24 +#define REG_RX_CTRL_NSAMPS_PP      _ctrl_base + 28 +#define REG_RX_CTRL_NCHANNELS      _ctrl_base + 32 + +using namespace uhd; + +class rx_dsp_core_200_impl : public rx_dsp_core_200{ +public: +    rx_dsp_core_200_impl( +        wb_iface::sptr iface, +        const size_t dsp_base, const size_t ctrl_base, +        const boost::uint32_t sid, const bool lingering_packet +    ): +        _iface(iface), _dsp_base(dsp_base), _ctrl_base(ctrl_base) +    { +        //This is a hack/fix for the lingering packet problem. +        //The caller should also flush the recv transports +        if (lingering_packet){ +            stream_cmd_t stream_cmd(stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_DONE); +            stream_cmd.num_samps = 1; +            issue_stream_command(stream_cmd); +        } + +        _iface->poke32(REG_RX_CTRL_CLEAR, 1); //reset +        _iface->poke32(REG_RX_CTRL_NCHANNELS, 1); +        _iface->poke32(REG_RX_CTRL_VRT_HDR, 0 +            | (0x1 << 28) //if data with stream id +            | (0x1 << 26) //has trailer +            | (0x3 << 22) //integer time other +            | (0x1 << 20) //fractional time sample count +        ); +        _iface->poke32(REG_RX_CTRL_VRT_SID, sid); +        _iface->poke32(REG_RX_CTRL_VRT_TLR, 0); +    } + +    void set_nsamps_per_packet(const size_t nsamps){ +        _iface->poke32(REG_RX_CTRL_NSAMPS_PP, nsamps); +    } + +    void issue_stream_command(const stream_cmd_t &stream_cmd){ +        UHD_ASSERT_THROW(stream_cmd.num_samps <= 0x3fffffff); +        _continuous_streaming = stream_cmd.stream_mode == stream_cmd_t::STREAM_MODE_START_CONTINUOUS; + +        //setup the mode to instruction flags +        typedef boost::tuple<bool, bool, bool> inst_t; +        static const uhd::dict<stream_cmd_t::stream_mode_t, inst_t> mode_to_inst = boost::assign::map_list_of +                                                                //reload, chain, samps +            (stream_cmd_t::STREAM_MODE_START_CONTINUOUS,   inst_t(true,  true,  false)) +            (stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS,    inst_t(false, false, false)) +            (stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_DONE, inst_t(false, false, true)) +            (stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_MORE, inst_t(false, true,  true)) +        ; + +        //setup the instruction flag values +        bool inst_reload, inst_chain, inst_samps; +        boost::tie(inst_reload, inst_chain, inst_samps) = mode_to_inst[stream_cmd.stream_mode]; + +        //calculate the word from flags and length +        boost::uint32_t cmd_word = 0; +        cmd_word |= boost::uint32_t((stream_cmd.stream_now)? 1 : 0) << 31; +        cmd_word |= boost::uint32_t((inst_chain)?            1 : 0) << 30; +        cmd_word |= boost::uint32_t((inst_reload)?           1 : 0) << 29; +        cmd_word |= (inst_samps)? stream_cmd.num_samps : ((inst_chain)? 1 : 0); + +        //issue the stream command +        _iface->poke32(REG_RX_CTRL_STREAM_CMD, cmd_word); +        _iface->poke32(REG_RX_CTRL_TIME_SECS, boost::uint32_t(stream_cmd.time_spec.get_full_secs())); +        _iface->poke32(REG_RX_CTRL_TIME_TICKS, stream_cmd.time_spec.get_tick_count(_tick_rate)); //latches the command +    } + +    void set_mux(const std::string &mode, const bool fe_swapped){ +        static const uhd::dict<std::string, boost::uint32_t> mode_to_mux = boost::assign::map_list_of +            ("IQ", 0) +            ("QI", FLAG_DSP_RX_MUX_SWAP_IQ) +            ("I", FLAG_DSP_RX_MUX_REAL_MODE) +            ("Q", FLAG_DSP_RX_MUX_SWAP_IQ | FLAG_DSP_RX_MUX_REAL_MODE) +        ; +        _iface->poke32(REG_DSP_RX_MUX, mode_to_mux[mode] ^ (fe_swapped? FLAG_DSP_RX_MUX_SWAP_IQ : 0)); +    } + +    void set_tick_rate(const double rate){ +        _tick_rate = rate; +    } + +    void set_link_rate(const double rate){ +        _link_rate = rate/sizeof(boost::uint32_t); //in samps/s +    } + +    double set_host_rate(const double rate){ +        const size_t decim_rate = uhd::clip<size_t>( +            boost::math::iround(_tick_rate/rate), size_t(std::ceil(_tick_rate/_link_rate)), 512 +        ); +        size_t decim = decim_rate; + +        //determine which half-band filters are activated +        int hb0 = 0, hb1 = 0; +        if (decim % 2 == 0){ +            hb0 = 1; +            decim /= 2; +        } +        if (decim % 2 == 0){ +            hb1 = 1; +            decim /= 2; +        } + +        _iface->poke32(REG_DSP_RX_DECIM, (hb1 << 9) | (hb0 << 8) | (decim & 0xff)); + +        return _tick_rate/decim_rate; +    } + +    double set_freq(const double freq_){ +        //correct for outside of rate (wrap around) +        double freq = std::fmod(freq_, _tick_rate); +        if (std::abs(freq) > _tick_rate/2.0) +            freq -= boost::math::sign(freq)*_tick_rate; + +        //calculate the freq register word (signed) +        UHD_ASSERT_THROW(std::abs(freq) <= _tick_rate/2.0); +        static const double scale_factor = std::pow(2.0, 32); +        const boost::int32_t freq_word = boost::int32_t(boost::math::round((freq / _tick_rate) * scale_factor)); + +        //update the actual frequency +        const double actual_freq = (double(freq_word) / scale_factor) * _tick_rate; + +        _iface->poke32(REG_DSP_RX_FREQ, boost::uint32_t(freq_word)); + +        return actual_freq; +    } + +    uhd::meta_range_t get_freq_range(void){ +        return uhd::meta_range_t(-_tick_rate/2, +_tick_rate/2, _tick_rate/std::pow(2.0, 32)); +    } + +    void handle_overflow(void){ +        if (_continuous_streaming) issue_stream_command(stream_cmd_t::STREAM_MODE_START_CONTINUOUS); +    } + +private: +    wb_iface::sptr _iface; +    const size_t _dsp_base, _ctrl_base; +    double _tick_rate, _link_rate; +    bool _continuous_streaming; +}; + +rx_dsp_core_200::sptr rx_dsp_core_200::make(wb_iface::sptr iface, const size_t dsp_base, const size_t ctrl_base, const boost::uint32_t sid, const bool lingering_packet){ +    return sptr(new rx_dsp_core_200_impl(iface, dsp_base, ctrl_base, sid, lingering_packet)); +} diff --git a/host/lib/usrp/cores/rx_dsp_core_200.hpp b/host/lib/usrp/cores/rx_dsp_core_200.hpp new file mode 100644 index 000000000..abe7bf817 --- /dev/null +++ b/host/lib/usrp/cores/rx_dsp_core_200.hpp @@ -0,0 +1,59 @@ +// +// 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_LIBUHD_USRP_RX_DSP_CORE_200_HPP +#define INCLUDED_LIBUHD_USRP_RX_DSP_CORE_200_HPP + +#include <uhd/config.hpp> +#include <uhd/types/ranges.hpp> +#include <boost/utility.hpp> +#include <boost/shared_ptr.hpp> +#include <uhd/types/stream_cmd.hpp> +#include "wb_iface.hpp" +#include <string> + +class rx_dsp_core_200 : boost::noncopyable{ +public: +    typedef boost::shared_ptr<rx_dsp_core_200> sptr; + +    static sptr make( +        wb_iface::sptr iface, +        const size_t dsp_base, const size_t ctrl_base, +        const boost::uint32_t sid, const bool lingering_packet = false +    ); + +    virtual void set_nsamps_per_packet(const size_t nsamps) = 0; + +    virtual void issue_stream_command(const uhd::stream_cmd_t &stream_cmd) = 0; + +    virtual void set_mux(const std::string &mode, const bool fe_swapped = false) = 0; + +    virtual void set_tick_rate(const double rate) = 0; + +    virtual void set_link_rate(const double rate) = 0; + +    virtual double set_host_rate(const double rate) = 0; + +    virtual uhd::meta_range_t get_freq_range(void) = 0; + +    virtual double set_freq(const double freq) = 0; + +    virtual void handle_overflow(void) = 0; + +}; + +#endif /* INCLUDED_LIBUHD_USRP_RX_DSP_CORE_200_HPP */ diff --git a/host/lib/usrp/cores/rx_frontend_core_200.cpp b/host/lib/usrp/cores/rx_frontend_core_200.cpp new file mode 100644 index 000000000..0e8220b49 --- /dev/null +++ b/host/lib/usrp/cores/rx_frontend_core_200.cpp @@ -0,0 +1,61 @@ +// +// 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 "rx_frontend_core_200.hpp" +#include <boost/math/special_functions/round.hpp> + +#define REG_RX_FE_SWAP_IQ             _base + 0 //lower bit +#define REG_RX_FE_MAG_CORRECTION      _base + 4 //18 bits +#define REG_RX_FE_PHASE_CORRECTION    _base + 8 //18 bits +#define REG_RX_FE_OFFSET_I            _base + 12 //18 bits +#define REG_RX_FE_OFFSET_Q            _base + 16 //18 bits + +static boost::uint32_t fs_to_bits(const double num, const size_t bits){ +    return boost::int32_t(boost::math::round(num * (1 << (bits-1)))); +} + + +class rx_frontend_core_200_impl : public rx_frontend_core_200{ +public: +    rx_frontend_core_200_impl(wb_iface::sptr iface, const size_t base): +        _iface(iface), _base(base) +    { +        //NOP +    } + +    void set_mux(const bool swap){ +        _iface->poke32(REG_RX_FE_SWAP_IQ, swap? 1 : 0); +    } + +    void set_offset(const std::complex<double> &off){ +        _iface->poke32(REG_RX_FE_OFFSET_I, fs_to_bits(off.real(), 24)); +        _iface->poke32(REG_RX_FE_OFFSET_Q, fs_to_bits(off.imag(), 24)); +    } + +    void set_correction(const std::complex<double> &cor){ +        _iface->poke32(REG_RX_FE_MAG_CORRECTION, fs_to_bits(std::abs(cor), 18)); +        _iface->poke32(REG_RX_FE_PHASE_CORRECTION, fs_to_bits(std::atan2(cor.real(), cor.imag()), 18)); +    } + +private: +    wb_iface::sptr _iface; +    const size_t _base; +}; + +rx_frontend_core_200::sptr rx_frontend_core_200::make(wb_iface::sptr iface, const size_t base){ +    return sptr(new rx_frontend_core_200_impl(iface, base)); +} diff --git a/host/lib/usrp/cores/rx_frontend_core_200.hpp b/host/lib/usrp/cores/rx_frontend_core_200.hpp new file mode 100644 index 000000000..a950e2bb7 --- /dev/null +++ b/host/lib/usrp/cores/rx_frontend_core_200.hpp @@ -0,0 +1,42 @@ +// +// 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_LIBUHD_USRP_TX_FRONTEND_CORE_200_HPP +#define INCLUDED_LIBUHD_USRP_TX_FRONTEND_CORE_200_HPP + +#include <uhd/config.hpp> +#include <boost/utility.hpp> +#include <boost/shared_ptr.hpp> +#include "wb_iface.hpp" +#include <complex> +#include <string> + +class rx_frontend_core_200 : boost::noncopyable{ +public: +    typedef boost::shared_ptr<rx_frontend_core_200> sptr; + +    static sptr make(wb_iface::sptr iface, const size_t base); + +    virtual void set_mux(const bool swap) = 0; + +    virtual void set_offset(const std::complex<double> &off) = 0; + +    virtual void set_correction(const std::complex<double> &cor) = 0; + +}; + +#endif /* INCLUDED_LIBUHD_USRP_TX_FRONTEND_CORE_200_HPP */ diff --git a/host/lib/usrp/cores/spi_core_100.cpp b/host/lib/usrp/cores/spi_core_100.cpp new file mode 100644 index 000000000..d11a499a9 --- /dev/null +++ b/host/lib/usrp/cores/spi_core_100.cpp @@ -0,0 +1,88 @@ +// +// 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 "spi_core_100.hpp" +#include <uhd/exception.hpp> +#include <uhd/utils/msg.hpp> +#include <boost/thread/thread.hpp> //sleep + +#define REG_SPI_TXRX0 _base + 0 +#define REG_SPI_TXRX1 _base + 4 +#define REG_SPI_TXRX2 _base + 8 +#define REG_SPI_TXRX3 _base + 12 +#define REG_SPI_CTRL  _base + 16 +#define REG_SPI_DIV   _base + 20 +#define REG_SPI_SS    _base + 24 + +//spi ctrl register bit definitions +#define SPI_CTRL_ASS      (1<<13) +#define SPI_CTRL_IE       (1<<12) +#define SPI_CTRL_LSB      (1<<11) +#define SPI_CTRL_TXNEG    (1<<10) //mosi edge, push on falling edge when 1 +#define SPI_CTRL_RXNEG    (1<< 9) //miso edge, latch on falling edge when 1 +#define SPI_CTRL_GO_BSY   (1<< 8) +#define SPI_CTRL_CHAR_LEN_MASK 0x7F + +using namespace uhd; + +class spi_core_100_impl : public spi_core_100{ +public: +    spi_core_100_impl(wb_iface::sptr iface, const size_t base): +        _iface(iface), _base(base) { /* NOP */} + +    boost::uint32_t transact_spi( +        int which_slave, +        const spi_config_t &config, +        boost::uint32_t data, +        size_t num_bits, +        bool readback +    ){ +        UHD_ASSERT_THROW(num_bits <= 32 and (num_bits % 8) == 0); + +        int edge_flags = ((config.miso_edge==spi_config_t::EDGE_FALL) ? SPI_CTRL_RXNEG : 0) | +                         ((config.mosi_edge==spi_config_t::EDGE_FALL) ? 0 : SPI_CTRL_TXNEG) +                         ; +        boost::uint16_t ctrl = SPI_CTRL_ASS | (SPI_CTRL_CHAR_LEN_MASK & num_bits) | edge_flags; + +        spi_wait(); +        _iface->poke16(REG_SPI_DIV, 0x0001); // = fpga_clk / 4 +        _iface->poke32(REG_SPI_SS, which_slave & 0xFFFF); +        _iface->poke32(REG_SPI_TXRX0, data); +        _iface->poke16(REG_SPI_CTRL, ctrl); +        _iface->poke16(REG_SPI_CTRL, ctrl | SPI_CTRL_GO_BSY); + +        if (not readback) return 0; +        spi_wait(); +        return _iface->peek32(REG_SPI_TXRX0); +    } + +private: +    void spi_wait(void) { +        for (size_t i = 0; i < 100; i++){ +            if ((_iface->peek16(REG_SPI_CTRL) & SPI_CTRL_GO_BSY) == 0) return; +            boost::this_thread::sleep(boost::posix_time::milliseconds(1)); +        } +        UHD_MSG(error) << "spi_core_100: spi_wait timeout" << std::endl; +    } + +    wb_iface::sptr _iface; +    const size_t _base; +}; + +spi_core_100::sptr spi_core_100::make(wb_iface::sptr iface, const size_t base){ +    return sptr(new spi_core_100_impl(iface, base)); +} diff --git a/host/lib/usrp/cores/spi_core_100.hpp b/host/lib/usrp/cores/spi_core_100.hpp new file mode 100644 index 000000000..87d328aaa --- /dev/null +++ b/host/lib/usrp/cores/spi_core_100.hpp @@ -0,0 +1,35 @@ +// +// 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_LIBUHD_USRP_SPI_CORE_100_HPP +#define INCLUDED_LIBUHD_USRP_SPI_CORE_100_HPP + +#include <uhd/config.hpp> +#include <uhd/types/serial.hpp> +#include <boost/utility.hpp> +#include <boost/shared_ptr.hpp> +#include "wb_iface.hpp" + +class spi_core_100 : boost::noncopyable, public uhd::spi_iface{ +public: +    typedef boost::shared_ptr<spi_core_100> sptr; + +    //! makes a new spi core from iface and slave base +    static sptr make(wb_iface::sptr iface, const size_t base); +}; + +#endif /* INCLUDED_LIBUHD_USRP_SPI_CORE_100_HPP */ diff --git a/host/lib/usrp/cores/time64_core_200.cpp b/host/lib/usrp/cores/time64_core_200.cpp new file mode 100644 index 000000000..23d1bdea2 --- /dev/null +++ b/host/lib/usrp/cores/time64_core_200.cpp @@ -0,0 +1,132 @@ +// +// 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 "time64_core_200.hpp" +#include <uhd/exception.hpp> +#include <uhd/utils/assert_has.hpp> +#include <boost/math/special_functions/round.hpp> + +#define REG_TIME64_SECS        _base + 0 +#define REG_TIME64_TICKS       _base + 4 +#define REG_TIME64_FLAGS       _base + 8 +#define REG_TIME64_IMM         _base + 12 +#define REG_TIME64_TPS         _base + 16 +#define REG_TIME64_MIMO_SYNC   _base + 20 //lower byte is delay cycles + +//pps flags (see above) +#define FLAG_TIME64_PPS_NEGEDGE (0 << 0) +#define FLAG_TIME64_PPS_POSEDGE (1 << 0) +#define FLAG_TIME64_PPS_SMA     (0 << 1) +#define FLAG_TIME64_PPS_MIMO    (1 << 1) //apparently not used + +#define FLAG_TIME64_LATCH_NOW 1 +#define FLAG_TIME64_LATCH_NEXT_PPS 0 + +#define FLAG_TIME64_MIMO_SYNC (1 << 8) + +using namespace uhd; + +class time64_core_200_impl : public time64_core_200{ +public: +    time64_core_200_impl( +        wb_iface::sptr iface, const size_t base, +        const readback_bases_type &readback_bases, +        const size_t mimo_delay_cycles +    ): +        _iface(iface), _base(base), +        _readback_bases(readback_bases), +        _mimo_delay_cycles(mimo_delay_cycles) +    { +        _sources.push_back("none"); +        _sources.push_back("external"); +        _sources.push_back("_external_"); +        if (_mimo_delay_cycles != 0) _sources.push_back("mimo"); +    } + +    void set_tick_rate(const double rate){ +        _tick_rate = rate; +        _iface->poke32(REG_TIME64_TPS, boost::math::iround(rate)); +    } + +    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_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"); +    } + +    uhd::time_spec_t get_time_last_pps(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_pps); +            const boost::uint32_t ticks = _iface->peek32(_readback_bases.rb_ticks_pps); +            if (secs != _iface->peek32(_readback_bases.rb_secs_pps)) continue; +            return time_spec_t(secs, ticks, _tick_rate); +        } +        throw uhd::runtime_error("time64_core_200: get time last pps timeout"); +    } + +    void set_time_now(const uhd::time_spec_t &time){ +        _iface->poke32(REG_TIME64_TICKS, time.get_tick_count(_tick_rate)); +        _iface->poke32(REG_TIME64_IMM, FLAG_TIME64_LATCH_NOW); +        _iface->poke32(REG_TIME64_SECS, boost::uint32_t(time.get_full_secs())); //latches all 3 +    } + +    void set_time_next_pps(const uhd::time_spec_t &time){ +        _iface->poke32(REG_TIME64_TICKS, time.get_tick_count(_tick_rate)); +        _iface->poke32(REG_TIME64_IMM, FLAG_TIME64_LATCH_NEXT_PPS); +        _iface->poke32(REG_TIME64_SECS, boost::uint32_t(time.get_full_secs())); //latches all 3 +    } + +    void set_time_source(const std::string &source){ +        assert_has(_sources, source, "time source"); + +        //setup pps flags +        if (source == "external"){ +            _iface->poke32(REG_TIME64_FLAGS, FLAG_TIME64_PPS_SMA | FLAG_TIME64_PPS_POSEDGE); +        } +        else if (source == "_external_"){ +            _iface->poke32(REG_TIME64_FLAGS, FLAG_TIME64_PPS_SMA | FLAG_TIME64_PPS_NEGEDGE); +        } + +        //setup mimo flags +        if (source == "mimo"){ +            _iface->poke32(REG_TIME64_MIMO_SYNC, FLAG_TIME64_MIMO_SYNC | (_mimo_delay_cycles & 0xff)); +        } +        else{ +            _iface->poke32(REG_TIME64_MIMO_SYNC, 0); +        } +    } + +    std::vector<std::string> get_time_sources(void){ +        return _sources; +    } + +private: +    wb_iface::sptr _iface; +    const size_t _base; +    const readback_bases_type _readback_bases; +    double _tick_rate; +    const size_t _mimo_delay_cycles; +    std::vector<std::string> _sources; +}; + +time64_core_200::sptr time64_core_200::make(wb_iface::sptr iface, const size_t base, const readback_bases_type &readback_bases, const size_t mimo_delay_cycles){ +    return sptr(new time64_core_200_impl(iface, base, readback_bases, mimo_delay_cycles)); +} diff --git a/host/lib/usrp/cores/time64_core_200.hpp b/host/lib/usrp/cores/time64_core_200.hpp new file mode 100644 index 000000000..ebd51a02f --- /dev/null +++ b/host/lib/usrp/cores/time64_core_200.hpp @@ -0,0 +1,61 @@ +// +// 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_LIBUHD_USRP_TIME64_CORE_200_HPP +#define INCLUDED_LIBUHD_USRP_TIME64_CORE_200_HPP + +#include <uhd/config.hpp> +#include <uhd/types/time_spec.hpp> +#include <boost/utility.hpp> +#include <boost/shared_ptr.hpp> +#include "wb_iface.hpp" +#include <string> +#include <vector> + +class time64_core_200 : boost::noncopyable{ +public: +    typedef boost::shared_ptr<time64_core_200> sptr; + +    struct readback_bases_type{ +        size_t rb_secs_now, rb_ticks_now; +        size_t rb_secs_pps, rb_ticks_pps; +    }; + +    //! makes a new time64 core from iface and slave base +    static sptr make( +        wb_iface::sptr iface, const size_t base, +        const readback_bases_type &readback_bases, +        const size_t mimo_delay_cycles = 0 // 0 means no-mimo +    ); + +    virtual void set_tick_rate(const double rate) = 0; + +    virtual uhd::time_spec_t get_time_now(void) = 0; + +    virtual uhd::time_spec_t get_time_last_pps(void) = 0; + +    virtual void set_time_now(const uhd::time_spec_t &time) = 0; + +    virtual void set_time_next_pps(const uhd::time_spec_t &time) = 0; + +    virtual void set_time_source(const std::string &source) = 0; + +    virtual std::vector<std::string> get_time_sources(void) = 0; + +}; + +#endif /* INCLUDED_LIBUHD_USRP_TIME64_CORE_200_HPP */ diff --git a/host/lib/usrp/cores/tx_dsp_core_200.cpp b/host/lib/usrp/cores/tx_dsp_core_200.cpp new file mode 100644 index 000000000..222ba589a --- /dev/null +++ b/host/lib/usrp/cores/tx_dsp_core_200.cpp @@ -0,0 +1,140 @@ +// +// 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 "tx_dsp_core_200.hpp" +#include <uhd/types/dict.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/algorithm.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/math/special_functions/round.hpp> +#include <boost/math/special_functions/sign.hpp> +#include <algorithm> +#include <cmath> + +#define REG_DSP_TX_FREQ          _dsp_base + 0 +#define REG_DSP_TX_SCALE_IQ      _dsp_base + 4 +#define REG_DSP_TX_INTERP        _dsp_base + 8 + +#define REG_TX_CTRL_NUM_CHAN        _ctrl_base + 0 +#define REG_TX_CTRL_CLEAR_STATE     _ctrl_base + 4 +#define REG_TX_CTRL_REPORT_SID      _ctrl_base + 8 +#define REG_TX_CTRL_POLICY          _ctrl_base + 12 +#define REG_TX_CTRL_CYCLES_PER_UP   _ctrl_base + 16 +#define REG_TX_CTRL_PACKETS_PER_UP  _ctrl_base + 20 + +#define FLAG_TX_CTRL_POLICY_WAIT          (0x1 << 0) +#define FLAG_TX_CTRL_POLICY_NEXT_PACKET   (0x1 << 1) +#define FLAG_TX_CTRL_POLICY_NEXT_BURST    (0x1 << 2) + +//enable flag for registers: cycles and packets per update packet +#define FLAG_TX_CTRL_UP_ENB              (1ul << 31) + +template <class T> T ceil_log2(T num){ +    return std::ceil(std::log(num)/std::log(T(2))); +} + +using namespace uhd; + +class tx_dsp_core_200_impl : public tx_dsp_core_200{ +public: +    tx_dsp_core_200_impl( +        wb_iface::sptr iface, +        const size_t dsp_base, const size_t ctrl_base, +        const boost::uint32_t sid +    ): +        _iface(iface), _dsp_base(dsp_base), _ctrl_base(ctrl_base) +    { +        //init the tx control registers +        _iface->poke32(REG_TX_CTRL_CLEAR_STATE, 1); //reset +        _iface->poke32(REG_TX_CTRL_NUM_CHAN, 0);    //1 channel +        _iface->poke32(REG_TX_CTRL_REPORT_SID, sid); +        _iface->poke32(REG_TX_CTRL_POLICY, FLAG_TX_CTRL_POLICY_NEXT_PACKET); +    } + +    void set_tick_rate(const double rate){ +        _tick_rate = rate; +    } + +    void set_link_rate(const double rate){ +        _link_rate = rate/sizeof(boost::uint32_t); //in samps/s +    } + +    double set_host_rate(const double rate){ +        const size_t interp_rate = uhd::clip<size_t>( +            boost::math::iround(_tick_rate/rate), size_t(std::ceil(_tick_rate/_link_rate)), 512 +        ); +        size_t interp = interp_rate; + +        //determine which half-band filters are activated +        int hb0 = 0, hb1 = 0; +        if (interp % 2 == 0){ +            hb0 = 1; +            interp /= 2; +        } +        if (interp % 2 == 0){ +            hb1 = 1; +            interp /= 2; +        } + +        _iface->poke32(REG_DSP_TX_INTERP, (hb1 << 9) | (hb0 << 8) | (interp & 0xff)); + +        // Calculate CIC interpolation (i.e., without halfband interpolators) +        // Calculate closest multiplier constant to reverse gain absent scale multipliers +        double rate_cubed = std::pow(double(interp & 0xff), 3); +        const boost::int16_t scale = boost::math::iround((4096*std::pow(2, ceil_log2(rate_cubed)))/(1.65*rate_cubed)); +        _iface->poke32(REG_DSP_TX_SCALE_IQ, (boost::uint32_t(scale) << 16) | (boost::uint32_t(scale) << 0)); + +        return _tick_rate/interp_rate; +    } + +    double set_freq(const double freq_){ +        //correct for outside of rate (wrap around) +        double freq = std::fmod(freq_, _tick_rate); +        if (std::abs(freq) > _tick_rate/2.0) +            freq -= boost::math::sign(freq)*_tick_rate; + +        //calculate the freq register word (signed) +        UHD_ASSERT_THROW(std::abs(freq) <= _tick_rate/2.0); +        static const double scale_factor = std::pow(2.0, 32); +        const boost::int32_t freq_word = boost::int32_t(boost::math::round((freq / _tick_rate) * scale_factor)); + +        //update the actual frequency +        const double actual_freq = (double(freq_word) / scale_factor) * _tick_rate; + +        _iface->poke32(REG_DSP_TX_FREQ, boost::uint32_t(freq_word)); + +        return actual_freq; +    } + +    uhd::meta_range_t get_freq_range(void){ +        return uhd::meta_range_t(-_tick_rate/2, +_tick_rate/2, _tick_rate/std::pow(2.0, 32)); +    } + +    void set_updates(const size_t cycles_per_up, const size_t packets_per_up){ +        _iface->poke32(REG_TX_CTRL_CYCLES_PER_UP,  (cycles_per_up  == 0)? 0 : (FLAG_TX_CTRL_UP_ENB | cycles_per_up)); +        _iface->poke32(REG_TX_CTRL_PACKETS_PER_UP, (packets_per_up == 0)? 0 : (FLAG_TX_CTRL_UP_ENB | packets_per_up)); +    } + +private: +    wb_iface::sptr _iface; +    const size_t _dsp_base, _ctrl_base; +    double _tick_rate, _link_rate; +}; + +tx_dsp_core_200::sptr tx_dsp_core_200::make(wb_iface::sptr iface, const size_t dsp_base, const size_t ctrl_base, const boost::uint32_t sid){ +    return sptr(new tx_dsp_core_200_impl(iface, dsp_base, ctrl_base, sid)); +} diff --git a/host/lib/usrp/cores/tx_dsp_core_200.hpp b/host/lib/usrp/cores/tx_dsp_core_200.hpp new file mode 100644 index 000000000..65f822558 --- /dev/null +++ b/host/lib/usrp/cores/tx_dsp_core_200.hpp @@ -0,0 +1,51 @@ +// +// 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_LIBUHD_USRP_TX_DSP_CORE_200_HPP +#define INCLUDED_LIBUHD_USRP_TX_DSP_CORE_200_HPP + +#include <uhd/config.hpp> +#include <uhd/types/ranges.hpp> +#include <boost/utility.hpp> +#include <boost/shared_ptr.hpp> +#include "wb_iface.hpp" + +class tx_dsp_core_200 : boost::noncopyable{ +public: +    typedef boost::shared_ptr<tx_dsp_core_200> sptr; + +    static sptr make( +        wb_iface::sptr iface, +        const size_t dsp_base, const size_t ctrl_base, +        const boost::uint32_t sid +    ); + +    virtual void set_tick_rate(const double rate) = 0; + +    virtual void set_link_rate(const double rate) = 0; + +    virtual double set_host_rate(const double rate) = 0; + +    virtual uhd::meta_range_t get_freq_range(void) = 0; + +    virtual double set_freq(const double freq) = 0; + +    virtual void set_updates(const size_t cycles_per_up, const size_t packets_per_up) = 0; + +}; + +#endif /* INCLUDED_LIBUHD_USRP_TX_DSP_CORE_200_HPP */ diff --git a/host/lib/usrp/cores/tx_frontend_core_200.cpp b/host/lib/usrp/cores/tx_frontend_core_200.cpp new file mode 100644 index 000000000..a7568a81e --- /dev/null +++ b/host/lib/usrp/cores/tx_frontend_core_200.cpp @@ -0,0 +1,70 @@ +// +// 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 "tx_frontend_core_200.hpp" +#include <uhd/types/dict.hpp> +#include <uhd/exception.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/math/special_functions/round.hpp> + +#define REG_TX_FE_DC_OFFSET_I         _base + 0 //24 bits +#define REG_TX_FE_DC_OFFSET_Q         _base + 4 //24 bits +#define REG_TX_FE_MAG_CORRECTION      _base + 8 //18 bits +#define REG_TX_FE_PHASE_CORRECTION    _base + 12 //18 bits +#define REG_TX_FE_MUX                 _base + 16 //8 bits (std output = 0x10, reversed = 0x01) + +static boost::uint32_t fs_to_bits(const double num, const size_t bits){ +    return boost::int32_t(boost::math::round(num * (1 << (bits-1)))); +} + + +class tx_frontend_core_200_impl : public tx_frontend_core_200{ +public: +    tx_frontend_core_200_impl(wb_iface::sptr iface, const size_t base): +        _iface(iface), _base(base) +    { +        //NOP +    } + +    void set_mux(const std::string &mode){ +        static const uhd::dict<std::string, boost::uint32_t> mode_to_mux = boost::assign::map_list_of +            ("IQ", (0x1 << 4) | (0x0 << 0)) //DAC0Q=DUC0Q, DAC0I=DUC0I +            ("QI", (0x0 << 4) | (0x1 << 0)) //DAC0Q=DUC0I, DAC0I=DUC0Q +            ("I",  (0xf << 4) | (0x0 << 0)) //DAC0Q=ZERO,  DAC0I=DUC0I +            ("Q",  (0x0 << 4) | (0xf << 0)) //DAC0Q=DUC0I, DAC0I=ZERO +        ; +        _iface->poke32(REG_TX_FE_MUX, mode_to_mux[mode]); +    } + +    void set_dc_offset(const std::complex<double> &off){ +        _iface->poke32(REG_TX_FE_DC_OFFSET_I, fs_to_bits(off.real(), 24)); +        _iface->poke32(REG_TX_FE_DC_OFFSET_Q, fs_to_bits(off.imag(), 24)); +    } + +    void set_correction(const std::complex<double> &cor){ +        _iface->poke32(REG_TX_FE_MAG_CORRECTION, fs_to_bits(std::abs(cor), 18)); +        _iface->poke32(REG_TX_FE_PHASE_CORRECTION, fs_to_bits(std::atan2(cor.real(), cor.imag()), 18)); +    } + +private: +    wb_iface::sptr _iface; +    const size_t _base; +}; + +tx_frontend_core_200::sptr tx_frontend_core_200::make(wb_iface::sptr iface, const size_t base){ +    return sptr(new tx_frontend_core_200_impl(iface, base)); +} diff --git a/host/lib/usrp/cores/tx_frontend_core_200.hpp b/host/lib/usrp/cores/tx_frontend_core_200.hpp new file mode 100644 index 000000000..9e4a7bc79 --- /dev/null +++ b/host/lib/usrp/cores/tx_frontend_core_200.hpp @@ -0,0 +1,42 @@ +// +// 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_LIBUHD_USRP_RX_FRONTEND_CORE_200_HPP +#define INCLUDED_LIBUHD_USRP_RX_FRONTEND_CORE_200_HPP + +#include <uhd/config.hpp> +#include <boost/utility.hpp> +#include <boost/shared_ptr.hpp> +#include "wb_iface.hpp" +#include <complex> +#include <string> + +class tx_frontend_core_200 : boost::noncopyable{ +public: +    typedef boost::shared_ptr<tx_frontend_core_200> sptr; + +    static sptr make(wb_iface::sptr iface, const size_t base); + +    virtual void set_mux(const std::string &mode) = 0; + +    virtual void set_dc_offset(const std::complex<double> &off) = 0; + +    virtual void set_correction(const std::complex<double> &cor) = 0; + +}; + +#endif /* INCLUDED_LIBUHD_USRP_RX_FRONTEND_CORE_200_HPP */ diff --git a/host/lib/usrp/cores/wb_iface.hpp b/host/lib/usrp/cores/wb_iface.hpp new file mode 100644 index 000000000..982594b21 --- /dev/null +++ b/host/lib/usrp/cores/wb_iface.hpp @@ -0,0 +1,60 @@ +// +// 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_LIBUHD_USRP_WB_IFACE_HPP +#define INCLUDED_LIBUHD_USRP_WB_IFACE_HPP + +#include <uhd/config.hpp> +#include <boost/cstdint.hpp> +#include <boost/shared_ptr.hpp> + +class wb_iface{ +public: +    typedef boost::shared_ptr<wb_iface> sptr; +    typedef boost::uint32_t wb_addr_type; + +    /*! +     * Write a register (32 bits) +     * \param addr the address +     * \param data the 32bit data +     */ +    virtual void poke32(wb_addr_type addr, boost::uint32_t data) = 0; + +    /*! +     * Read a register (32 bits) +     * \param addr the address +     * \return the 32bit data +     */ +    virtual boost::uint32_t peek32(wb_addr_type addr) = 0; + +    /*! +     * Write a register (16 bits) +     * \param addr the address +     * \param data the 16bit data +     */ +    virtual void poke16(wb_addr_type addr, boost::uint16_t data) = 0; + +    /*! +     * Read a register (16 bits) +     * \param addr the address +     * \return the 16bit data +     */ +    virtual boost::uint16_t peek16(wb_addr_type addr) = 0; + +}; + +#endif /* INCLUDED_LIBUHD_USRP_WB_IFACE_HPP */ diff --git a/host/lib/usrp/dboard/db_basic_and_lf.cpp b/host/lib/usrp/dboard/db_basic_and_lf.cpp index 566e24d97..ff93f1d89 100644 --- a/host/lib/usrp/dboard/db_basic_and_lf.cpp +++ b/host/lib/usrp/dboard/db_basic_and_lf.cpp @@ -15,7 +15,6 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/types/dict.hpp>  #include <uhd/types/ranges.hpp>  #include <uhd/utils/assert_has.hpp> @@ -162,6 +161,10 @@ void basic_rx::rx_get(const wax::obj &key_, wax::obj &val){          val = prop_names_t(1, ""); //vector of 1 empty string          return; +    case SUBDEV_PROP_SENSOR_NAMES: +        val = prop_names_t(1, ""); //vector of 1 empty string +        return; +      case SUBDEV_PROP_CONNECTION:          val = sd_name_to_conn[get_subdev_name()];          return; @@ -268,6 +271,10 @@ void basic_tx::tx_get(const wax::obj &key_, wax::obj &val){          val = prop_names_t(1, ""); //vector of 1 empty string          return; +    case SUBDEV_PROP_SENSOR_NAMES: +        val = prop_names_t(1, ""); //vector of 1 empty string +        return; +      case SUBDEV_PROP_CONNECTION:          val = sd_name_to_conn[get_subdev_name()];          return; diff --git a/host/lib/usrp/dboard/db_dbsrx.cpp b/host/lib/usrp/dboard/db_dbsrx.cpp index cfe06db29..c65c52590 100644 --- a/host/lib/usrp/dboard/db_dbsrx.cpp +++ b/host/lib/usrp/dboard/db_dbsrx.cpp @@ -28,7 +28,6 @@  #include <uhd/types/ranges.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/types/dict.hpp> -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/usrp/dboard_base.hpp>  #include <uhd/usrp/dboard_manager.hpp>  #include <boost/assign/list_of.hpp> diff --git a/host/lib/usrp/dboard/db_dbsrx2.cpp b/host/lib/usrp/dboard/db_dbsrx2.cpp index aaced7a5d..93bab5aec 100644 --- a/host/lib/usrp/dboard/db_dbsrx2.cpp +++ b/host/lib/usrp/dboard/db_dbsrx2.cpp @@ -25,7 +25,6 @@  #include <uhd/types/ranges.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/types/dict.hpp> -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/usrp/dboard_base.hpp>  #include <uhd/usrp/dboard_manager.hpp>  #include <boost/assign/list_of.hpp> diff --git a/host/lib/usrp/dboard/db_rfx.cpp b/host/lib/usrp/dboard/db_rfx.cpp index 61f9130d4..14129ef72 100644 --- a/host/lib/usrp/dboard/db_rfx.cpp +++ b/host/lib/usrp/dboard/db_rfx.cpp @@ -34,7 +34,6 @@  #include "adf4360_regs.hpp"  #include <uhd/types/dict.hpp> -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/types/ranges.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/utils/assert_has.hpp> diff --git a/host/lib/usrp/dboard/db_sbx.cpp b/host/lib/usrp/dboard/db_sbx.cpp index 6ca89b81a..aa9556e77 100644 --- a/host/lib/usrp/dboard/db_sbx.cpp +++ b/host/lib/usrp/dboard/db_sbx.cpp @@ -74,7 +74,6 @@  #include "adf4350_regs.hpp"  #include <uhd/types/dict.hpp> -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/types/ranges.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/utils/assert_has.hpp> diff --git a/host/lib/usrp/dboard/db_tvrx.cpp b/host/lib/usrp/dboard/db_tvrx.cpp index 1ff0fb785..3b8b276e0 100644 --- a/host/lib/usrp/dboard/db_tvrx.cpp +++ b/host/lib/usrp/dboard/db_tvrx.cpp @@ -35,7 +35,6 @@  #include <uhd/types/ranges.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/types/dict.hpp> -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/usrp/dboard_base.hpp>  #include <uhd/usrp/dboard_manager.hpp>  #include <boost/assign/list_of.hpp> diff --git a/host/lib/usrp/dboard/db_tvrx2.cpp b/host/lib/usrp/dboard/db_tvrx2.cpp index 39ff90d79..23f203b8c 100644 --- a/host/lib/usrp/dboard/db_tvrx2.cpp +++ b/host/lib/usrp/dboard/db_tvrx2.cpp @@ -59,7 +59,6 @@  #include <uhd/types/ranges.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/types/dict.hpp> -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/usrp/dboard_base.hpp>  #include <uhd/usrp/dboard_manager.hpp>  #include <boost/assign/list_of.hpp> diff --git a/host/lib/usrp/dboard/db_unknown.cpp b/host/lib/usrp/dboard/db_unknown.cpp index 6cacab231..0587d015c 100644 --- a/host/lib/usrp/dboard/db_unknown.cpp +++ b/host/lib/usrp/dboard/db_unknown.cpp @@ -15,7 +15,6 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/types/ranges.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/static.hpp> @@ -142,6 +141,10 @@ void unknown_rx::rx_get(const wax::obj &key_, wax::obj &val){          val = prop_names_t(1, ""); //vector of 1 empty string          return; +    case SUBDEV_PROP_SENSOR_NAMES: +        val = prop_names_t(1, ""); //vector of 1 empty string +        return; +      case SUBDEV_PROP_CONNECTION:          val = SUBDEV_CONN_COMPLEX_IQ;          return; @@ -238,6 +241,10 @@ void unknown_tx::tx_get(const wax::obj &key_, wax::obj &val){          val = prop_names_t(1, ""); //vector of 1 empty string          return; +    case SUBDEV_PROP_SENSOR_NAMES: +        val = prop_names_t(1, ""); //vector of 1 empty string +        return; +      case SUBDEV_PROP_CONNECTION:          val = SUBDEV_CONN_COMPLEX_IQ;          return; diff --git a/host/lib/usrp/dboard/db_wbx_common.cpp b/host/lib/usrp/dboard/db_wbx_common.cpp index 1a016e89c..81aba6426 100644 --- a/host/lib/usrp/dboard/db_wbx_common.cpp +++ b/host/lib/usrp/dboard/db_wbx_common.cpp @@ -61,7 +61,6 @@  #include "adf4350_regs.hpp"  #include <uhd/utils/log.hpp>  #include <uhd/types/dict.hpp> -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/types/ranges.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/utils/assert_has.hpp> diff --git a/host/lib/usrp/dboard/db_wbx_simple.cpp b/host/lib/usrp/dboard/db_wbx_simple.cpp index 602ce389d..ae466b08a 100644 --- a/host/lib/usrp/dboard/db_wbx_simple.cpp +++ b/host/lib/usrp/dboard/db_wbx_simple.cpp @@ -26,7 +26,6 @@  #include <uhd/utils/static.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/usrp/dboard_manager.hpp> -#include <uhd/usrp/subdev_props.hpp>  #include <boost/assign/list_of.hpp>  using namespace uhd; diff --git a/host/lib/usrp/dboard/db_xcvr2450.cpp b/host/lib/usrp/dboard/db_xcvr2450.cpp index fcd05ea04..b88eb2a95 100644 --- a/host/lib/usrp/dboard/db_xcvr2450.cpp +++ b/host/lib/usrp/dboard/db_xcvr2450.cpp @@ -56,7 +56,6 @@  #include <uhd/types/ranges.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/types/dict.hpp> -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/usrp/dboard_base.hpp>  #include <uhd/usrp/dboard_manager.hpp>  #include <boost/assign/list_of.hpp> diff --git a/host/lib/usrp/dboard_eeprom.cpp b/host/lib/usrp/dboard_eeprom.cpp index 0dc3471f7..b3cb54c1c 100644 --- a/host/lib/usrp/dboard_eeprom.cpp +++ b/host/lib/usrp/dboard_eeprom.cpp @@ -133,7 +133,7 @@ void dboard_eeprom_t::load(i2c_iface &iface, boost::uint8_t addr){      }  } -void dboard_eeprom_t::store(i2c_iface &iface, boost::uint8_t addr){ +void dboard_eeprom_t::store(i2c_iface &iface, boost::uint8_t addr) const{      byte_vector_t bytes(DB_EEPROM_CLEN, 0); //defaults to all zeros      bytes[DB_EEPROM_MAGIC] = DB_EEPROM_MAGIC_VALUE; diff --git a/host/lib/usrp/dboard_manager.cpp b/host/lib/usrp/dboard_manager.cpp index 3cc2ca3c0..fae3d35b3 100644 --- a/host/lib/usrp/dboard_manager.cpp +++ b/host/lib/usrp/dboard_manager.cpp @@ -17,7 +17,6 @@  #include "dboard_ctor_args.hpp"  #include <uhd/usrp/dboard_manager.hpp> -#include <uhd/usrp/subdev_props.hpp>  #include <uhd/utils/msg.hpp>  #include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp> @@ -404,3 +403,127 @@ void dboard_manager_impl::set_nice_dboard_if(void){          this->get_tx_subdev(sd_name)[SUBDEV_PROP_ENABLED] = false;      }  } + +/*********************************************************************** + * Populate a properties tree from a subdev waxy object + **********************************************************************/ +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> + +static sensor_value_t get_sensor(wax::obj subdev, const std::string &name){ +    return subdev[named_prop_t(SUBDEV_PROP_SENSOR, name)].as<sensor_value_t>(); +} + +static void set_gain(wax::obj subdev, const std::string &name, const double gain){ +    subdev[named_prop_t(SUBDEV_PROP_GAIN, name)] = gain; +} + +static double get_gain(wax::obj subdev, const std::string &name){ +    return subdev[named_prop_t(SUBDEV_PROP_GAIN, name)].as<double>(); +} + +static meta_range_t get_gain_range(wax::obj subdev, const std::string &name){ +    return subdev[named_prop_t(SUBDEV_PROP_GAIN_RANGE, name)].as<meta_range_t>(); +} + +static void set_freq(wax::obj subdev, const double freq){ +    subdev[SUBDEV_PROP_FREQ] = freq; +} + +static double get_freq(wax::obj subdev){ +    return subdev[SUBDEV_PROP_FREQ].as<double>(); +} + +static meta_range_t get_freq_range(wax::obj subdev){ +    return subdev[SUBDEV_PROP_FREQ_RANGE].as<meta_range_t>(); +} + +static void set_ant(wax::obj subdev, const std::string &ant){ +    subdev[SUBDEV_PROP_ANTENNA] = ant; +} + +static std::string get_ant(wax::obj subdev){ +    return subdev[SUBDEV_PROP_ANTENNA].as<std::string>(); +} + +static std::vector<std::string> get_ants(wax::obj subdev){ +    return subdev[SUBDEV_PROP_ANTENNA_NAMES].as<std::vector<std::string> >(); +} + +static std::string get_conn(wax::obj subdev){ +    switch(subdev[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>()){ +    case SUBDEV_CONN_COMPLEX_IQ: return "IQ"; +    case SUBDEV_CONN_COMPLEX_QI: return "QI"; +    case SUBDEV_CONN_REAL_I: return "I"; +    case SUBDEV_CONN_REAL_Q: return "Q"; +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +static bool get_use_lo_off(wax::obj subdev){ +    return subdev[SUBDEV_PROP_USE_LO_OFFSET].as<bool>(); +} + +static bool get_set_enb(wax::obj subdev, const bool enb){ +    subdev[SUBDEV_PROP_ENABLED] = enb; +    return subdev[SUBDEV_PROP_ENABLED].as<bool>(); +} + +static void set_bw(wax::obj subdev, const double freq){ +    subdev[SUBDEV_PROP_BANDWIDTH] = freq; +} + +static double get_bw(wax::obj subdev){ +    return subdev[SUBDEV_PROP_BANDWIDTH].as<double>(); +} + +void dboard_manager::populate_prop_tree_from_subdev( +    property_tree::sptr tree, +    const property_tree::path_type &root, +    wax::obj subdev +){ +    tree->create<std::string>(root / "name").set(subdev[SUBDEV_PROP_NAME].as<std::string>()); + +    const prop_names_t sensor_names = subdev[SUBDEV_PROP_SENSOR_NAMES].as<prop_names_t>(); +    BOOST_FOREACH(const std::string &name, sensor_names){ +        tree->create<sensor_value_t>(root / "sensors" / name) +            .publish(boost::bind(&get_sensor, subdev, name)); +    } + +    const prop_names_t gain_names = subdev[SUBDEV_PROP_GAIN_NAMES].as<prop_names_t>(); +    tree->create<int>(root / "gains"); //phony property so this dir exists +    BOOST_FOREACH(const std::string &name, gain_names){ +        tree->create<double>(root / "gains" / name / "value") +            .publish(boost::bind(&get_gain, subdev, name)) +            .subscribe(boost::bind(&set_gain, subdev, name, _1)); +        tree->create<meta_range_t>(root / "gains" / name / "range") +            .publish(boost::bind(&get_gain_range, subdev, name)); +    } + +    tree->create<double>(root / "freq/value") +        .publish(boost::bind(&get_freq, subdev)) +        .subscribe(boost::bind(&set_freq, subdev, _1)); + +    tree->create<meta_range_t>(root / "freq/range") +        .publish(boost::bind(&get_freq_range, subdev)); + +    tree->create<std::string>(root / "antenna/value") +        .publish(boost::bind(&get_ant, subdev)) +        .subscribe(boost::bind(&set_ant, subdev, _1)); + +    tree->create<std::vector<std::string> >(root / "antenna/options") +        .publish(boost::bind(&get_ants, subdev)); + +    tree->create<std::string>(root / "connection") +        .publish(boost::bind(&get_conn, subdev)); + +    tree->create<bool>(root / "enabled") +        .coerce(boost::bind(&get_set_enb, subdev, _1)); + +    tree->create<bool>(root / "use_lo_offset") +        .publish(boost::bind(&get_use_lo_off, subdev)); + +    tree->create<double>(root / "bandwidth/value") +        .publish(boost::bind(&get_bw, subdev)) +        .subscribe(boost::bind(&set_bw, subdev, _1)); +} diff --git a/host/lib/usrp/dsp_utils.cpp b/host/lib/usrp/dsp_utils.cpp deleted file mode 100644 index 2686e895b..000000000 --- a/host/lib/usrp/dsp_utils.cpp +++ /dev/null @@ -1,141 +0,0 @@ -// -// Copyright 2010-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 <uhd/usrp/dsp_utils.hpp> -#include <uhd/types/dict.hpp> -#include <uhd/exception.hpp> -#include <boost/assign/list_of.hpp> -#include <boost/tuple/tuple.hpp> -#include <boost/math/special_functions/round.hpp> -#include <boost/math/special_functions/sign.hpp> -#include <algorithm> -#include <cmath> - -using namespace uhd; -using namespace uhd::usrp; - -template <class T> T ceil_log2(T num){ -    return std::ceil(std::log(num)/std::log(T(2))); -} - -/*! - *     3                   2                   1                   0 - *   1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 - *  +-------------------------------+-------+-------+-------+-------+ - *  |                                               | DDC0Q | DDC0I | - *  +-------------------------------+-------+-------+-------+-------+ - */ -boost::uint32_t dsp_type1::calc_rx_mux_word(subdev_conn_t subdev_conn){ -    switch(subdev_conn){ -    case SUBDEV_CONN_COMPLEX_IQ: return (0x1 << 4) | (0x0 << 0); //DDC0Q=ADC0Q, DDC0I=ADC0I -    case SUBDEV_CONN_COMPLEX_QI: return (0x0 << 4) | (0x1 << 0); //DDC0Q=ADC0I, DDC0I=ADC0Q -    case SUBDEV_CONN_REAL_I:     return (0xf << 4) | (0x0 << 0); //DDC0Q=ZERO,  DDC0I=ADC0I -    case SUBDEV_CONN_REAL_Q:     return (0xf << 4) | (0x1 << 0); //DDC0Q=ZERO,  DDC0I=ADC0Q -    default:                     UHD_THROW_INVALID_CODE_PATH(); -    } -} - -/*! - *     3                   2                   1                   0 - *   1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 - *  +-------------------------------+-------+-------+-------+-------+ - *  |                                               | DAC0Q | DAC0I | - *  +-------------------------------+-------+-------+-------+-------+ - */ -boost::uint32_t dsp_type1::calc_tx_mux_word(subdev_conn_t subdev_conn){ -    switch(subdev_conn){ -    case SUBDEV_CONN_COMPLEX_IQ: return (0x1 << 4) | (0x0 << 0); //DAC0Q=DUC0Q, DAC0I=DUC0I -    case SUBDEV_CONN_COMPLEX_QI: return (0x0 << 4) | (0x1 << 0); //DAC0Q=DUC0I, DAC0I=DUC0Q -    case SUBDEV_CONN_REAL_I:     return (0xf << 4) | (0x0 << 0); //DAC0Q=ZERO,  DAC0I=DUC0I -    case SUBDEV_CONN_REAL_Q:     return (0x0 << 4) | (0xf << 0); //DAC0Q=DUC0I, DAC0I=ZERO -    default:                     UHD_THROW_INVALID_CODE_PATH(); -    } -} - -boost::uint32_t dsp_type1::calc_cordic_word_and_update( -    double &freq, double codec_rate -){ -    //correct for outside of rate (wrap around) -    freq = std::fmod(freq, codec_rate); -    if (std::abs(freq) > codec_rate/2.0) -        freq -= boost::math::sign(freq)*codec_rate; - -    //calculate the freq register word (signed) -    UHD_ASSERT_THROW(std::abs(freq) <= codec_rate/2.0); -    static const double scale_factor = std::pow(2.0, 32); -    boost::int32_t freq_word = boost::int32_t(boost::math::round((freq / codec_rate) * scale_factor)); - -    //update the actual frequency -    freq = (double(freq_word) / scale_factor) * codec_rate; - -    return boost::uint32_t(freq_word); -} - -boost::uint32_t dsp_type1::calc_cic_filter_word(unsigned rate){ -    int hb0 = 0, hb1 = 0; -    if (not (rate & 0x1)){ -        hb0 = 1; -        rate /= 2; -    } -    if (not (rate & 0x1)){ -        hb1 = 1; -        rate /= 2; -    } -    return (hb1 << 9) | (hb0 << 8) | (rate & 0xff); -} - -boost::uint32_t dsp_type1::calc_iq_scale_word( -    boost::int16_t i, boost::int16_t q -){ -    return (boost::uint32_t(i) << 16) | (boost::uint32_t(q) << 0); -} - -boost::uint32_t dsp_type1::calc_iq_scale_word(unsigned rate){ -    // Calculate CIC interpolation (i.e., without halfband interpolators) -    unsigned tmp_rate = calc_cic_filter_word(rate) & 0xff; - -    // Calculate closest multiplier constant to reverse gain absent scale multipliers -    double rate_cubed = std::pow(double(tmp_rate), 3); -    boost::int16_t scale = boost::math::iround((4096*std::pow(2, ceil_log2(rate_cubed)))/(1.65*rate_cubed)); -    return calc_iq_scale_word(scale, scale); -} - -boost::uint32_t dsp_type1::calc_stream_cmd_word(const stream_cmd_t &stream_cmd){ -    UHD_ASSERT_THROW(stream_cmd.num_samps <= 0x3fffffff); - -    //setup the mode to instruction flags -    typedef boost::tuple<bool, bool, bool> inst_t; -    static const uhd::dict<stream_cmd_t::stream_mode_t, inst_t> mode_to_inst = boost::assign::map_list_of -                                                            //reload, chain, samps -        (stream_cmd_t::STREAM_MODE_START_CONTINUOUS,   inst_t(true,  true,  false)) -        (stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS,    inst_t(false, false, false)) -        (stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_DONE, inst_t(false, false, true)) -        (stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_MORE, inst_t(false, true,  true)) -    ; - -    //setup the instruction flag values -    bool inst_reload, inst_chain, inst_samps; -    boost::tie(inst_reload, inst_chain, inst_samps) = mode_to_inst[stream_cmd.stream_mode]; - -    //calculate the word from flags and length -    boost::uint32_t word = 0; -    word |= boost::uint32_t((stream_cmd.stream_now)? 1 : 0) << 31; -    word |= boost::uint32_t((inst_chain)?            1 : 0) << 30; -    word |= boost::uint32_t((inst_reload)?           1 : 0) << 29; -    word |= (inst_samps)? stream_cmd.num_samps : ((inst_chain)? 1 : 0); -    return word; -} diff --git a/host/lib/usrp/e100/CMakeLists.txt b/host/lib/usrp/e100/CMakeLists.txt index 15133ad5e..ac9d8c655 100644 --- a/host/lib/usrp/e100/CMakeLists.txt +++ b/host/lib/usrp/e100/CMakeLists.txt @@ -22,28 +22,19 @@  ########################################################################  # Conditionally configure the USRP-E100 support  ######################################################################## -LIBUHD_REGISTER_COMPONENT("USRP-E100" ENABLE_E100 OFF "ENABLE_LIBUHD;LINUX" OFF) +LIBUHD_REGISTER_COMPONENT("E100" ENABLE_E100 OFF "ENABLE_LIBUHD;LINUX" OFF)  IF(ENABLE_E100)      INCLUDE_DIRECTORIES(${CMAKE_CURRENT_SOURCE_DIR}/include)      LIBUHD_APPEND_SOURCES(          ${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}/dboard_impl.cpp          ${CMAKE_CURRENT_SOURCE_DIR}/dboard_iface.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/dsp_impl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/fpga_downloader.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/io_impl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/mboard_impl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/e100_ctrl.cpp          ${CMAKE_CURRENT_SOURCE_DIR}/e100_impl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/e100_impl.hpp -        ${CMAKE_CURRENT_SOURCE_DIR}/e100_iface.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/e100_iface.hpp          ${CMAKE_CURRENT_SOURCE_DIR}/e100_mmap_zero_copy.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/e100_regs.hpp +        ${CMAKE_CURRENT_SOURCE_DIR}/fpga_downloader.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/io_impl.cpp      )  ENDIF(ENABLE_E100) diff --git a/host/lib/usrp/e100/clock_ctrl.cpp b/host/lib/usrp/e100/clock_ctrl.cpp index ff64d9ca7..6acb13528 100644 --- a/host/lib/usrp/e100/clock_ctrl.cpp +++ b/host/lib/usrp/e100/clock_ctrl.cpp @@ -167,7 +167,7 @@ static clock_settings_type get_clock_settings(double rate){   **********************************************************************/  class e100_clock_ctrl_impl : public e100_clock_ctrl{  public: -    e100_clock_ctrl_impl(e100_iface::sptr iface, double master_clock_rate){ +    e100_clock_ctrl_impl(spi_iface::sptr iface, double master_clock_rate){          _iface = iface;          _chan_rate = 0.0;          _out_rate = 0.0; @@ -294,10 +294,8 @@ public:          if (_out_rate == rate) return;          if (rate == 61.44e6) set_clock_settings_with_external_vcxo(rate);          else                 set_clock_settings_with_internal_vco(rate); -        //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(E100_REG_TIME64_TPS, boost::uint32_t(get_fpga_clock_rate()));      }      double get_fpga_clock_rate(void){ @@ -421,7 +419,7 @@ public:      }  private: -    e100_iface::sptr _iface; +    spi_iface::sptr _iface;      ad9522_regs_t _ad9522_regs;      double _out_rate; //rate at the fpga and codec      double _chan_rate; //rate before final dividers @@ -507,6 +505,6 @@ private:  /***********************************************************************   * Clock Control Make   **********************************************************************/ -e100_clock_ctrl::sptr e100_clock_ctrl::make(e100_iface::sptr iface, double master_clock_rate){ +e100_clock_ctrl::sptr e100_clock_ctrl::make(spi_iface::sptr iface, double master_clock_rate){      return sptr(new e100_clock_ctrl_impl(iface, master_clock_rate));  } diff --git a/host/lib/usrp/e100/clock_ctrl.hpp b/host/lib/usrp/e100/clock_ctrl.hpp index f3a6de0fa..7c16649d3 100644 --- a/host/lib/usrp/e100/clock_ctrl.hpp +++ b/host/lib/usrp/e100/clock_ctrl.hpp @@ -18,7 +18,7 @@  #ifndef INCLUDED_USRP_E100_CLOCK_CTRL_HPP  #define INCLUDED_USRP_E100_CLOCK_CTRL_HPP -#include "e100_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 usrp_e100 iface object +     * \param iface the spi iface object       * \param master clock rate the FPGA rate       * \return the clock control object       */ -    static sptr make(e100_iface::sptr iface, double master_clock_rate); +    static sptr make(uhd::spi_iface::sptr iface, double master_clock_rate);      /*!       * Set the rate of the fpga clock line. diff --git a/host/lib/usrp/e100/codec_ctrl.cpp b/host/lib/usrp/e100/codec_ctrl.cpp index a796d5cc5..6efeb10e8 100644 --- a/host/lib/usrp/e100/codec_ctrl.cpp +++ b/host/lib/usrp/e100/codec_ctrl.cpp @@ -38,7 +38,7 @@ const gain_range_t e100_codec_ctrl::rx_pga_gain_range(0, 20, 1);  class e100_codec_ctrl_impl : public e100_codec_ctrl{  public:      //structors -    e100_codec_ctrl_impl(e100_iface::sptr iface); +    e100_codec_ctrl_impl(spi_iface::sptr iface);      ~e100_codec_ctrl_impl(void);      //aux adc and dac control @@ -52,7 +52,7 @@ public:      double get_rx_pga_gain(char);  private: -    e100_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); @@ -61,7 +61,7 @@ private:  /***********************************************************************   * Codec Control Structors   **********************************************************************/ -e100_codec_ctrl_impl::e100_codec_ctrl_impl(e100_iface::sptr iface){ +e100_codec_ctrl_impl::e100_codec_ctrl_impl(spi_iface::sptr iface){      _iface = iface;      //soft reset @@ -275,6 +275,6 @@ void e100_codec_ctrl_impl::recv_reg(boost::uint8_t addr){  /***********************************************************************   * Codec Control Make   **********************************************************************/ -e100_codec_ctrl::sptr e100_codec_ctrl::make(e100_iface::sptr iface){ +e100_codec_ctrl::sptr e100_codec_ctrl::make(spi_iface::sptr iface){      return sptr(new e100_codec_ctrl_impl(iface));  } diff --git a/host/lib/usrp/e100/codec_ctrl.hpp b/host/lib/usrp/e100/codec_ctrl.hpp index 22d0390f5..707f6f521 100644 --- a/host/lib/usrp/e100/codec_ctrl.hpp +++ b/host/lib/usrp/e100/codec_ctrl.hpp @@ -18,7 +18,7 @@  #ifndef INCLUDED_USRP_E100_CODEC_CTRL_HPP  #define INCLUDED_USRP_E100_CODEC_CTRL_HPP -#include "e100_iface.hpp" +#include <uhd/types/serial.hpp>  #include <uhd/types/ranges.hpp>  #include <boost/shared_ptr.hpp>  #include <boost/utility.hpp> @@ -37,10 +37,10 @@ public:      /*!       * Make a new codec control object. -     * \param iface the usrp_e100 iface object +     * \param iface the spi iface object       * \return the codec control object       */ -    static sptr make(e100_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/e100/codec_impl.cpp b/host/lib/usrp/e100/codec_impl.cpp deleted file mode 100644 index 26743d173..000000000 --- a/host/lib/usrp/e100/codec_impl.cpp +++ /dev/null @@ -1,149 +0,0 @@ -// -// Copyright 2010-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 "e100_impl.hpp" -#include <uhd/exception.hpp> -#include <uhd/usrp/codec_props.hpp> -#include <boost/bind.hpp> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * Helper Methods - **********************************************************************/ -void e100_impl::codec_init(void){ -    //make proxies -    _rx_codec_proxy = wax_obj_proxy::make( -        boost::bind(&e100_impl::rx_codec_get, this, _1, _2), -        boost::bind(&e100_impl::rx_codec_set, this, _1, _2) -    ); -    _tx_codec_proxy = wax_obj_proxy::make( -        boost::bind(&e100_impl::tx_codec_get, this, _1, _2), -        boost::bind(&e100_impl::tx_codec_set, this, _1, _2) -    ); -} - -/*********************************************************************** - * RX Codec Properties - **********************************************************************/ -static const std::string ad9862_pga_gain_name = "ad9862 pga"; - -void e100_impl::rx_codec_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_NAME: -        val = std::string("usrp-e adc - ad9522"); -        return; - -    case CODEC_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case CODEC_PROP_GAIN_NAMES: -        val = prop_names_t(1, ad9862_pga_gain_name); -        return; - -    case CODEC_PROP_GAIN_RANGE: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        val = e100_codec_ctrl::rx_pga_gain_range; -        return; - -    case CODEC_PROP_GAIN_I: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        val = _codec_ctrl->get_rx_pga_gain('A'); -        return; - -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        val = _codec_ctrl->get_rx_pga_gain('B'); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void e100_impl::rx_codec_set(const wax::obj &key_, const wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the set request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_GAIN_I: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        _codec_ctrl->set_rx_pga_gain(val.as<double>(), 'A'); -        return; - -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        _codec_ctrl->set_rx_pga_gain(val.as<double>(), 'B'); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} - -/*********************************************************************** - * TX Codec Properties - **********************************************************************/ -void e100_impl::tx_codec_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_NAME: -        val = std::string("usrp-e dac - ad9522"); -        return; - -    case CODEC_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case CODEC_PROP_GAIN_NAMES: -        val = prop_names_t(1, ad9862_pga_gain_name); -        return; - -    case CODEC_PROP_GAIN_RANGE: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        val = e100_codec_ctrl::tx_pga_gain_range; -        return; - -    case CODEC_PROP_GAIN_I: //only one gain for I and Q -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        val = _codec_ctrl->get_tx_pga_gain(); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void e100_impl::tx_codec_set(const wax::obj &key_, const wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the set request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_GAIN_I: //only one gain for I and Q -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == ad9862_pga_gain_name); -        _codec_ctrl->set_tx_pga_gain(val.as<double>()); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/e100/dboard_iface.cpp b/host/lib/usrp/e100/dboard_iface.cpp index 43e05aa57..d45577bd9 100644 --- a/host/lib/usrp/e100/dboard_iface.cpp +++ b/host/lib/usrp/e100/dboard_iface.cpp @@ -15,7 +15,8 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include "e100_iface.hpp" +#include "wb_iface.hpp" +#include <uhd/types/serial.hpp>  #include "e100_regs.hpp"  #include "clock_ctrl.hpp"  #include "codec_ctrl.hpp" @@ -29,15 +30,19 @@ using namespace uhd;  using namespace uhd::usrp;  using namespace boost::assign; -class usrp_e100_dboard_iface : public dboard_iface{ +class e100_dboard_iface : public dboard_iface{  public: -    usrp_e100_dboard_iface( -        e100_iface::sptr iface, +    e100_dboard_iface( +        wb_iface::sptr wb_iface, +        i2c_iface::sptr i2c_iface, +        spi_iface::sptr spi_iface,          e100_clock_ctrl::sptr clock,          e100_codec_ctrl::sptr codec      ){ -        _iface = iface; +        _wb_iface = wb_iface; +        _i2c_iface = i2c_iface; +        _spi_iface = spi_iface;          _clock = clock;          _codec = codec; @@ -45,11 +50,11 @@ 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(E100_REG_GPIO_RX_DBG, 0); -        _iface->poke16(E100_REG_GPIO_TX_DBG, 0); +        _wb_iface->poke16(E100_REG_GPIO_RX_DBG, 0); +        _wb_iface->poke16(E100_REG_GPIO_TX_DBG, 0);      } -    ~usrp_e100_dboard_iface(void){ +    ~e100_dboard_iface(void){          /* NOP */      } @@ -94,7 +99,9 @@ public:      double get_codec_rate(unit_t);  private: -    e100_iface::sptr _iface; +    wb_iface::sptr _wb_iface; +    i2c_iface::sptr _i2c_iface; +    spi_iface::sptr _spi_iface;      e100_clock_ctrl::sptr _clock;      e100_codec_ctrl::sptr _codec;  }; @@ -102,25 +109,27 @@ private:  /***********************************************************************   * Make Function   **********************************************************************/ -dboard_iface::sptr make_usrp_e100_dboard_iface( -    e100_iface::sptr iface, +dboard_iface::sptr make_e100_dboard_iface( +    wb_iface::sptr wb_iface, +    i2c_iface::sptr i2c_iface, +    spi_iface::sptr spi_iface,      e100_clock_ctrl::sptr clock,      e100_codec_ctrl::sptr codec  ){ -    return dboard_iface::sptr(new usrp_e100_dboard_iface(iface, clock, codec)); +    return dboard_iface::sptr(new e100_dboard_iface(wb_iface, i2c_iface, spi_iface, clock, codec));  }  /***********************************************************************   * Clock Rates   **********************************************************************/ -void usrp_e100_dboard_iface::set_clock_rate(unit_t unit, double rate){ +void e100_dboard_iface::set_clock_rate(unit_t unit, double rate){      switch(unit){      case UNIT_RX: return _clock->set_rx_dboard_clock_rate(rate);      case UNIT_TX: return _clock->set_tx_dboard_clock_rate(rate);      }  } -std::vector<double> usrp_e100_dboard_iface::get_clock_rates(unit_t unit){ +std::vector<double> e100_dboard_iface::get_clock_rates(unit_t unit){      switch(unit){      case UNIT_RX: return _clock->get_rx_dboard_clock_rates();      case UNIT_TX: return _clock->get_tx_dboard_clock_rates(); @@ -128,7 +137,7 @@ std::vector<double> usrp_e100_dboard_iface::get_clock_rates(unit_t unit){      }  } -double usrp_e100_dboard_iface::get_clock_rate(unit_t unit){ +double e100_dboard_iface::get_clock_rate(unit_t unit){      switch(unit){      case UNIT_RX: return _clock->get_rx_clock_rate();      case UNIT_TX: return _clock->get_tx_clock_rate(); @@ -136,51 +145,51 @@ double usrp_e100_dboard_iface::get_clock_rate(unit_t unit){      UHD_THROW_INVALID_CODE_PATH();  } -void usrp_e100_dboard_iface::set_clock_enabled(unit_t unit, bool enb){ +void e100_dboard_iface::set_clock_enabled(unit_t unit, bool enb){      switch(unit){      case UNIT_RX: return _clock->enable_rx_dboard_clock(enb);      case UNIT_TX: return _clock->enable_tx_dboard_clock(enb);      }  } -double usrp_e100_dboard_iface::get_codec_rate(unit_t){ +double e100_dboard_iface::get_codec_rate(unit_t){      return _clock->get_fpga_clock_rate();  }  /***********************************************************************   * GPIO   **********************************************************************/ -void usrp_e100_dboard_iface::_set_pin_ctrl(unit_t unit, boost::uint16_t value){ +void e100_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(E100_REG_GPIO_RX_SEL, value); return; -    case UNIT_TX: _iface->poke16(E100_REG_GPIO_TX_SEL, value); return; +    case UNIT_RX: _wb_iface->poke16(E100_REG_GPIO_RX_SEL, value); return; +    case UNIT_TX: _wb_iface->poke16(E100_REG_GPIO_TX_SEL, value); return;      }  } -void usrp_e100_dboard_iface::_set_gpio_ddr(unit_t unit, boost::uint16_t value){ +void e100_dboard_iface::_set_gpio_ddr(unit_t unit, boost::uint16_t value){      switch(unit){ -    case UNIT_RX: _iface->poke16(E100_REG_GPIO_RX_DDR, value); return; -    case UNIT_TX: _iface->poke16(E100_REG_GPIO_TX_DDR, value); return; +    case UNIT_RX: _wb_iface->poke16(E100_REG_GPIO_RX_DDR, value); return; +    case UNIT_TX: _wb_iface->poke16(E100_REG_GPIO_TX_DDR, value); return;      }  } -void usrp_e100_dboard_iface::_set_gpio_out(unit_t unit, boost::uint16_t value){ +void e100_dboard_iface::_set_gpio_out(unit_t unit, boost::uint16_t value){      switch(unit){ -    case UNIT_RX: _iface->poke16(E100_REG_GPIO_RX_IO, value); return; -    case UNIT_TX: _iface->poke16(E100_REG_GPIO_TX_IO, value); return; +    case UNIT_RX: _wb_iface->poke16(E100_REG_GPIO_RX_IO, value); return; +    case UNIT_TX: _wb_iface->poke16(E100_REG_GPIO_TX_IO, value); return;      }  } -boost::uint16_t usrp_e100_dboard_iface::read_gpio(unit_t unit){ +boost::uint16_t e100_dboard_iface::read_gpio(unit_t unit){      switch(unit){ -    case UNIT_RX: return _iface->peek16(E100_REG_GPIO_RX_IO); -    case UNIT_TX: return _iface->peek16(E100_REG_GPIO_TX_IO); +    case UNIT_RX: return _wb_iface->peek16(E100_REG_GPIO_RX_IO); +    case UNIT_TX: return _wb_iface->peek16(E100_REG_GPIO_TX_IO);      default: UHD_THROW_INVALID_CODE_PATH();      }  } -void usrp_e100_dboard_iface::_set_atr_reg(unit_t unit, atr_reg_t atr, boost::uint16_t value){ +void e100_dboard_iface::_set_atr_reg(unit_t unit, atr_reg_t atr, boost::uint16_t value){      //define mapping of unit to atr regs to register address      static const uhd::dict<          unit_t, uhd::dict<atr_reg_t, boost::uint32_t> @@ -198,10 +207,10 @@ void usrp_e100_dboard_iface::_set_atr_reg(unit_t unit, atr_reg_t atr, boost::uin              (ATR_REG_FULL_DUPLEX, E100_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 usrp_e100_dboard_iface::set_gpio_debug(unit_t unit, int which){ +void e100_dboard_iface::set_gpio_debug(unit_t unit, int which){      //set this unit to all outputs      this->set_gpio_ddr(unit, 0xffff); @@ -213,13 +222,13 @@ void usrp_e100_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(E100_REG_GPIO_RX_DBG, 0xffff); -        _iface->poke16(E100_REG_GPIO_RX_SEL, dbg_sels); +        _wb_iface->poke16(E100_REG_GPIO_RX_DBG, 0xffff); +        _wb_iface->poke16(E100_REG_GPIO_RX_SEL, dbg_sels);          return;      case UNIT_TX: -        _iface->poke16(E100_REG_GPIO_TX_DBG, 0xffff); -        _iface->poke16(E100_REG_GPIO_TX_SEL, dbg_sels); +        _wb_iface->poke16(E100_REG_GPIO_TX_DBG, 0xffff); +        _wb_iface->poke16(E100_REG_GPIO_TX_SEL, dbg_sels);          return;      }  } @@ -240,39 +249,39 @@ static boost::uint32_t unit_to_otw_spi_dev(dboard_iface::unit_t unit){      UHD_THROW_INVALID_CODE_PATH();  } -void usrp_e100_dboard_iface::write_spi( +void e100_dboard_iface::write_spi(      unit_t unit,      const spi_config_t &config,      boost::uint32_t data,      size_t num_bits  ){ -    _iface->write_spi(unit_to_otw_spi_dev(unit), config, data, num_bits); +    _spi_iface->write_spi(unit_to_otw_spi_dev(unit), config, data, num_bits);  } -boost::uint32_t usrp_e100_dboard_iface::read_write_spi( +boost::uint32_t e100_dboard_iface::read_write_spi(      unit_t unit,      const spi_config_t &config,      boost::uint32_t data,      size_t num_bits  ){ -    return _iface->read_spi(unit_to_otw_spi_dev(unit), config, data, num_bits); +    return _spi_iface->read_spi(unit_to_otw_spi_dev(unit), config, data, num_bits);  }  /***********************************************************************   * I2C   **********************************************************************/ -void usrp_e100_dboard_iface::write_i2c(boost::uint8_t addr, const byte_vector_t &bytes){ -    return _iface->write_i2c(addr, bytes); +void e100_dboard_iface::write_i2c(boost::uint8_t addr, const byte_vector_t &bytes){ +    return _i2c_iface->write_i2c(addr, bytes);  } -byte_vector_t usrp_e100_dboard_iface::read_i2c(boost::uint8_t addr, size_t num_bytes){ -    return _iface->read_i2c(addr, num_bytes); +byte_vector_t e100_dboard_iface::read_i2c(boost::uint8_t addr, size_t num_bytes){ +    return _i2c_iface->read_i2c(addr, num_bytes);  }  /***********************************************************************   * Aux DAX/ADC   **********************************************************************/ -void usrp_e100_dboard_iface::write_aux_dac(dboard_iface::unit_t, aux_dac_t which, double value){ +void e100_dboard_iface::write_aux_dac(dboard_iface::unit_t, aux_dac_t which, double value){      //same aux dacs for each unit      static const uhd::dict<aux_dac_t, e100_codec_ctrl::aux_dac_t> which_to_aux_dac = map_list_of          (AUX_DAC_A, e100_codec_ctrl::AUX_DAC_A) @@ -283,7 +292,7 @@ void usrp_e100_dboard_iface::write_aux_dac(dboard_iface::unit_t, aux_dac_t which      _codec->write_aux_dac(which_to_aux_dac[which], value);  } -double usrp_e100_dboard_iface::read_aux_adc(dboard_iface::unit_t unit, aux_adc_t which){ +double e100_dboard_iface::read_aux_adc(dboard_iface::unit_t unit, aux_adc_t which){      static const uhd::dict<          unit_t, uhd::dict<aux_adc_t, e100_codec_ctrl::aux_adc_t>      > unit_to_which_to_aux_adc = map_list_of diff --git a/host/lib/usrp/e100/dboard_impl.cpp b/host/lib/usrp/e100/dboard_impl.cpp deleted file mode 100644 index 86481e70a..000000000 --- a/host/lib/usrp/e100/dboard_impl.cpp +++ /dev/null @@ -1,185 +0,0 @@ -// -// Copyright 2010-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 "e100_impl.hpp" -#include "e100_regs.hpp" -#include <uhd/exception.hpp> -#include <uhd/usrp/dboard_props.hpp> -#include <uhd/usrp/subdev_props.hpp> -#include <uhd/usrp/misc_utils.hpp> -#include <boost/bind.hpp> -#include <iostream> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * Dboard Initialization - **********************************************************************/ -void e100_impl::dboard_init(void){ -    //read the dboard eeprom to extract the dboard ids -    _rx_db_eeprom.load(*_iface, I2C_ADDR_RX_DB); -    _tx_db_eeprom.load(*_iface, I2C_ADDR_TX_DB); -    _gdb_eeprom.load(*_iface, I2C_ADDR_TX_DB ^ 5); - -    //create a new dboard interface and manager -    _dboard_iface = make_usrp_e100_dboard_iface( -        _iface, _clock_ctrl, _codec_ctrl -    ); -    _dboard_manager = dboard_manager::make( -        _rx_db_eeprom.id, -        ((_gdb_eeprom.id == dboard_id_t::none())? _tx_db_eeprom : _gdb_eeprom).id, -        _dboard_iface -    ); - -    //setup the dboard proxies -    _rx_dboard_proxy = wax_obj_proxy::make( -        boost::bind(&e100_impl::rx_dboard_get, this, _1, _2), -        boost::bind(&e100_impl::rx_dboard_set, this, _1, _2) -    ); -    _tx_dboard_proxy = wax_obj_proxy::make( -        boost::bind(&e100_impl::tx_dboard_get, this, _1, _2), -        boost::bind(&e100_impl::tx_dboard_set, this, _1, _2) -    ); -} - -/*********************************************************************** - * RX Dboard Get - **********************************************************************/ -void e100_impl::rx_dboard_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_NAME: -        val = std::string("usrp-e dboard (rx unit)"); -        return; - -    case DBOARD_PROP_SUBDEV: -        val = _dboard_manager->get_rx_subdev(key.name); -        return; - -    case DBOARD_PROP_SUBDEV_NAMES: -        val = _dboard_manager->get_rx_subdev_names(); -        return; - -    case DBOARD_PROP_DBOARD_EEPROM: -        val = _rx_db_eeprom; -        return; - -    case DBOARD_PROP_DBOARD_IFACE: -        val = _dboard_iface; -        return; - -    case DBOARD_PROP_CODEC: -        val = _rx_codec_proxy->get_link(); -        return; - -    case DBOARD_PROP_GAIN_GROUP: -        val = make_gain_group( -            _rx_db_eeprom.id, -            _dboard_manager->get_rx_subdev(key.name), -            _rx_codec_proxy->get_link(), -            GAIN_GROUP_POLICY_RX -        ); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * RX Dboard Set - **********************************************************************/ -void e100_impl::rx_dboard_set(const wax::obj &key, const wax::obj &val){ -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_DBOARD_EEPROM: -        _rx_db_eeprom = val.as<dboard_eeprom_t>(); -        _rx_db_eeprom.store(*_iface, I2C_ADDR_RX_DB); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} - -/*********************************************************************** - * TX Dboard Get - **********************************************************************/ -void e100_impl::tx_dboard_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_NAME: -        val = std::string("usrp-e dboard (tx unit)"); -        return; - -    case DBOARD_PROP_SUBDEV: -        val = _dboard_manager->get_tx_subdev(key.name); -        return; - -    case DBOARD_PROP_SUBDEV_NAMES: -        val = _dboard_manager->get_tx_subdev_names(); -        return; - -    case DBOARD_PROP_DBOARD_EEPROM: -        val = _tx_db_eeprom; -        return; - -    case DBOARD_PROP_GBOARD_EEPROM: -        val = _gdb_eeprom; -        return; - -    case DBOARD_PROP_DBOARD_IFACE: -        val = _dboard_iface; -        return; - -    case DBOARD_PROP_CODEC: -        val = _tx_codec_proxy->get_link(); -        return; - -    case DBOARD_PROP_GAIN_GROUP: -        val = make_gain_group( -            _tx_db_eeprom.id, -            _dboard_manager->get_tx_subdev(key.name), -            _tx_codec_proxy->get_link(), -            GAIN_GROUP_POLICY_TX -        ); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * TX Dboard Set - **********************************************************************/ -void e100_impl::tx_dboard_set(const wax::obj &key, const wax::obj &val){ -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_DBOARD_EEPROM: -        _tx_db_eeprom = val.as<dboard_eeprom_t>(); -        _tx_db_eeprom.store(*_iface, I2C_ADDR_TX_DB); -        return; - -    case DBOARD_PROP_GBOARD_EEPROM: -        _gdb_eeprom = val.as<dboard_eeprom_t>(); -        _gdb_eeprom.store(*_iface, I2C_ADDR_TX_DB ^ 5); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/e100/dsp_impl.cpp b/host/lib/usrp/e100/dsp_impl.cpp deleted file mode 100644 index fc65609a0..000000000 --- a/host/lib/usrp/e100/dsp_impl.cpp +++ /dev/null @@ -1,217 +0,0 @@ -// -// Copyright 2010-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 "e100_impl.hpp" -#include "e100_regs.hpp" -#include <uhd/usrp/dsp_utils.hpp> -#include <uhd/usrp/dsp_props.hpp> -#include <boost/math/special_functions/round.hpp> -#include <boost/bind.hpp> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * DSP impl and methods - **********************************************************************/ -struct e100_impl::dsp_impl{ -    uhd::dict<size_t, size_t> ddc_decim; -    uhd::dict<size_t, double> ddc_freq; -    uhd::dict<size_t, size_t> duc_interp; -    uhd::dict<size_t, double> duc_freq; -}; - -/*********************************************************************** - * RX DDC Initialization - **********************************************************************/ -void e100_impl::dsp_init(void){ -    //create new dsp impl -    _dsp_impl = UHD_PIMPL_MAKE(dsp_impl, ()); - -    //bind and initialize the rx dsps -    for (size_t i = 0; i < E100_NUM_RX_DSPS; i++){ -        _rx_dsp_proxies[str(boost::format("DSP%d")%i)] = wax_obj_proxy::make( -            boost::bind(&e100_impl::ddc_get, this, _1, _2, i), -            boost::bind(&e100_impl::ddc_set, this, _1, _2, i) -        ); - -        //initial config and update -        ddc_set(DSP_PROP_FREQ_SHIFT, double(0), i); -        ddc_set(DSP_PROP_HOST_RATE, double(_clock_ctrl->get_fpga_clock_rate()/16), i); - -        //setup the rx control registers -        _iface->poke32(E100_REG_RX_CTRL_CLEAR(i), 1); //reset -        _iface->poke32(E100_REG_RX_CTRL_NSAMPS_PP(i), this->get_max_recv_samps_per_packet()); -        _iface->poke32(E100_REG_RX_CTRL_NCHANNELS(i), 1); -        _iface->poke32(E100_REG_RX_CTRL_VRT_HDR(i), 0 -            | (0x1 << 28) //if data with stream id -            | (0x1 << 26) //has trailer -            | (0x3 << 22) //integer time other -            | (0x1 << 20) //fractional time sample count -        ); -        _iface->poke32(E100_REG_RX_CTRL_VRT_SID(i), E100_DSP_SID_BASE + i); -        _iface->poke32(E100_REG_RX_CTRL_VRT_TLR(i), 0); -        _iface->poke32(E100_REG_TIME64_TPS, size_t(_clock_ctrl->get_fpga_clock_rate())); -    } - -    //bind and initialize the tx dsps -    for (size_t i = 0; i < E100_NUM_TX_DSPS; i++){ -        _tx_dsp_proxies[str(boost::format("DSP%d")%i)] = wax_obj_proxy::make( -            boost::bind(&e100_impl::duc_get, this, _1, _2, i), -            boost::bind(&e100_impl::duc_set, this, _1, _2, i) -        ); - -        //initial config and update -        duc_set(DSP_PROP_FREQ_SHIFT, double(0), i); -        duc_set(DSP_PROP_HOST_RATE, double(_clock_ctrl->get_fpga_clock_rate()/16), i); - -        //init the tx control registers -        _iface->poke32(E100_REG_TX_CTRL_CLEAR_STATE, 1); //reset -        _iface->poke32(E100_REG_TX_CTRL_NUM_CHAN, 0);    //1 channel -        _iface->poke32(E100_REG_TX_CTRL_REPORT_SID, E100_ASYNC_SID); -        _iface->poke32(E100_REG_TX_CTRL_POLICY, E100_FLAG_TX_CTRL_POLICY_NEXT_PACKET); -    } -} - -/*********************************************************************** - * RX DDC Get - **********************************************************************/ -void e100_impl::ddc_get(const wax::obj &key_, wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ -    case DSP_PROP_NAME: -        val = str(boost::format("%s ddc%d") % _iface->get_cname() % which_dsp); -        return; - -    case DSP_PROP_OTHERS: -        val = prop_names_t(); //empty -        return; - -    case DSP_PROP_FREQ_SHIFT: -        val = _dsp_impl->ddc_freq[which_dsp]; -        return; - -    case DSP_PROP_CODEC_RATE: -        val = _clock_ctrl->get_fpga_clock_rate(); -        return; - -    case DSP_PROP_HOST_RATE: -        val = _clock_ctrl->get_fpga_clock_rate()/_dsp_impl->ddc_decim[which_dsp]; -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * RX DDC Set - **********************************************************************/ -void e100_impl::ddc_set(const wax::obj &key_, const wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ - -    case DSP_PROP_STREAM_CMD: -        issue_ddc_stream_cmd(val.as<stream_cmd_t>(), which_dsp); -        return; - -    case DSP_PROP_FREQ_SHIFT:{ -            double new_freq = val.as<double>(); -            _iface->poke32(E100_REG_DSP_RX_FREQ(which_dsp), -                dsp_type1::calc_cordic_word_and_update(new_freq, _clock_ctrl->get_fpga_clock_rate()) -            ); -            _dsp_impl->ddc_freq[which_dsp] = new_freq; //shadow -        } -        return; - -    case DSP_PROP_HOST_RATE:{ -            _dsp_impl->ddc_decim[which_dsp] = boost::math::iround(_clock_ctrl->get_fpga_clock_rate()/val.as<double>()); - -            //set the decimation -            _iface->poke32(E100_REG_DSP_RX_DECIM(which_dsp), dsp_type1::calc_cic_filter_word(_dsp_impl->ddc_decim[which_dsp])); -        } -        this->update_xport_channel_mapping(); //rate changed -> update -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} - -/*********************************************************************** - * TX DUC Get - **********************************************************************/ -void e100_impl::duc_get(const wax::obj &key_, wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ -    case DSP_PROP_NAME: -        val = str(boost::format("%s duc%d") % _iface->get_cname() % which_dsp); -        return; - -    case DSP_PROP_OTHERS: -        val = prop_names_t(); //empty -        return; - -    case DSP_PROP_FREQ_SHIFT: -        val = _dsp_impl->duc_freq[which_dsp]; -        return; - -    case DSP_PROP_CODEC_RATE: -        val = _clock_ctrl->get_fpga_clock_rate(); -        return; - -    case DSP_PROP_HOST_RATE: -        val = _clock_ctrl->get_fpga_clock_rate()/_dsp_impl->duc_interp[which_dsp]; -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * TX DUC Set - **********************************************************************/ -void e100_impl::duc_set(const wax::obj &key_, const wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ - -    case DSP_PROP_FREQ_SHIFT:{ -            double new_freq = val.as<double>(); -            _iface->poke32(E100_REG_DSP_TX_FREQ, -                dsp_type1::calc_cordic_word_and_update(new_freq, _clock_ctrl->get_fpga_clock_rate()) -            ); -            _dsp_impl->duc_freq[which_dsp] = new_freq; //shadow -        } -        return; - -    case DSP_PROP_HOST_RATE:{ -            _dsp_impl->duc_interp[which_dsp] = boost::math::iround(_clock_ctrl->get_fpga_clock_rate()/val.as<double>()); - -            //set the interpolation -            _iface->poke32(E100_REG_DSP_TX_INTERP_RATE, dsp_type1::calc_cic_filter_word(_dsp_impl->duc_interp[which_dsp])); - -            //set the scaling -            _iface->poke32(E100_REG_DSP_TX_SCALE_IQ, dsp_type1::calc_iq_scale_word(_dsp_impl->duc_interp[which_dsp])); -        } -        this->update_xport_channel_mapping(); //rate changed -> update -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/e100/e100_iface.cpp b/host/lib/usrp/e100/e100_ctrl.cpp index 1bf33ae5b..87f7855d3 100644 --- a/host/lib/usrp/e100/e100_iface.cpp +++ b/host/lib/usrp/e100/e100_ctrl.cpp @@ -1,5 +1,5 @@  // -// Copyright 2010-2011 Ettus Research LLC +// 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 @@ -15,7 +15,7 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include "e100_iface.hpp" +#include "e100_ctrl.hpp"  #include "e100_regs.hpp"  #include <uhd/exception.hpp>  #include <uhd/utils/msg.hpp> @@ -25,12 +25,9 @@  #include <boost/thread/thread.hpp> //sleep  #include <boost/thread/mutex.hpp>  #include <boost/format.hpp> -#include <linux/i2c-dev.h> -#include <linux/i2c.h>  #include <fstream>  using namespace uhd; -using namespace uhd::usrp;  /***********************************************************************   * Sysfs GPIO wrapper class @@ -71,21 +68,53 @@ private:      std::fstream _value_file;  }; -//We only init the gpios when we have to use them (in the aux spi call). -//This way, the device discovery cannot unexport them from another process. -struct iface_gpios_type{ -    typedef boost::shared_ptr<iface_gpios_type> sptr; -    iface_gpios_type(void): +/*********************************************************************** + * Aux spi implementation + **********************************************************************/ +class aux_spi_iface_impl : public spi_iface{ +public: +    aux_spi_iface_impl(void):          spi_sclk_gpio(65, "out"),          spi_sen_gpio(186, "out"),          spi_mosi_gpio(145, "out"),          spi_miso_gpio(147, "in"){} + +    boost::uint32_t transact_spi( +        int, const spi_config_t &, //not used params +        boost::uint32_t bits, +        size_t num_bits, +        bool readback +    ){ +        boost::uint32_t rb_bits = 0; +        this->spi_sen_gpio(0); + +        for (size_t i = 0; i < num_bits; i++){ +            this->spi_sclk_gpio(0); +            this->spi_mosi_gpio((bits >> (num_bits-i-1)) & 0x1); +            boost::this_thread::sleep(boost::posix_time::microseconds(10)); +            if (readback) rb_bits = (rb_bits << 1) | this->spi_miso_gpio(); +            this->spi_sclk_gpio(1); +            boost::this_thread::sleep(boost::posix_time::microseconds(10)); +        } + +        this->spi_sen_gpio(1); +        boost::this_thread::sleep(boost::posix_time::microseconds(100)); +        return rb_bits; +    } + +private:      gpio spi_sclk_gpio, spi_sen_gpio, spi_mosi_gpio, spi_miso_gpio;  }; +uhd::spi_iface::sptr e100_ctrl::make_aux_spi_iface(void){ +    return uhd::spi_iface::sptr(new aux_spi_iface_impl()); +} +  /***********************************************************************   * I2C device node implementation wrapper   **********************************************************************/ +#include <linux/i2c-dev.h> +#include <linux/i2c.h>  class i2c_dev_iface : public i2c_iface{  public:      i2c_dev_iface(const std::string &node){ @@ -141,17 +170,24 @@ public:  private: int _node_fd;  }; +uhd::i2c_iface::sptr e100_ctrl::make_dev_i2c_iface(const std::string &node){ +    return uhd::i2c_iface::sptr(new i2c_dev_iface(node)); +} +  /*********************************************************************** - * USRP-E100 interface implementation + * USRP-E100 control implementation   **********************************************************************/ -class e100_iface_impl : public e100_iface{ +class e100_ctrl_impl : public e100_ctrl{  public:      int get_file_descriptor(void){          return _node_fd;      } -    void open(const std::string &node){ +    /******************************************************************* +     * Structors +     ******************************************************************/ +    e100_ctrl_impl(const std::string &node){          UHD_MSG(status) << "Opening device node " << node << "..." << std::endl;          //open the device node and check file descriptor @@ -170,28 +206,10 @@ public:          //perform a global reset after opening          this->poke32(E100_REG_GLOBAL_RESET, 0); - -        //and now is a good time to init the i2c -        this->i2c_init();      } -    void close(void){ +    ~e100_ctrl_impl(void){          ::close(_node_fd); -        _node_fd = -1; -    } - -    /******************************************************************* -     * Structors -     ******************************************************************/ -    e100_iface_impl(void): -        _node_fd(-1), -        _i2c_dev_iface(i2c_dev_iface("/dev/i2c-3")) -    { -        mb_eeprom = mboard_eeprom_t(get_i2c_dev_iface(), mboard_eeprom_t::MAP_E100); -    } - -    ~e100_iface_impl(void){ -        if (_node_fd >= 0) this->close();      }      /******************************************************************* @@ -206,18 +224,10 @@ public:              ));          }      } - -    /******************************************************************* -     * I2C device node interface -     ******************************************************************/ -    i2c_iface &get_i2c_dev_iface(void){ -        return _i2c_dev_iface; -    } -      /*******************************************************************       * Peek and Poke       ******************************************************************/ -    void poke32(boost::uint32_t addr, boost::uint32_t value){ +    void poke32(wb_addr_type addr, boost::uint32_t value){          //load the data struct          usrp_e_ctl32 data;          data.offset = addr; @@ -228,7 +238,7 @@ public:          this->ioctl(USRP_E_WRITE_CTL32, &data);      } -    void poke16(boost::uint32_t addr, boost::uint16_t value){ +    void poke16(wb_addr_type addr, boost::uint16_t value){          //load the data struct          usrp_e_ctl16 data;          data.offset = addr; @@ -239,7 +249,7 @@ public:          this->ioctl(USRP_E_WRITE_CTL16, &data);      } -    boost::uint32_t peek32(boost::uint32_t addr){ +    boost::uint32_t peek32(wb_addr_type addr){          //load the data struct          usrp_e_ctl32 data;          data.offset = addr; @@ -251,7 +261,7 @@ public:          return data.buf[0];      } -    boost::uint16_t peek16(boost::uint32_t addr){ +    boost::uint16_t peek16(wb_addr_type addr){          //load the data struct          usrp_e_ctl16 data;          data.offset = addr; @@ -263,162 +273,14 @@ public:          return data.buf[0];      } -    /******************************************************************* -     * I2C -     ******************************************************************/ -    static const boost::uint32_t i2c_datarate = 400000; -    static const boost::uint32_t wishbone_clk = 64000000; //FIXME should go somewhere else - -    void i2c_init(void) { -        //init I2C FPGA interface. -        poke16(E100_REG_I2C_CTRL, 0x0000); -        //set prescalers to operate at 400kHz: WB_CLK is 64MHz... -        boost::uint16_t prescaler = wishbone_clk / (i2c_datarate*5) - 1; -        poke16(E100_REG_I2C_PRESCALER_LO, prescaler & 0xFF); -        poke16(E100_REG_I2C_PRESCALER_HI, (prescaler >> 8) & 0xFF); -        poke16(E100_REG_I2C_CTRL, I2C_CTRL_EN); //enable I2C core -    } - -    void i2c_wait(void){ -        for (size_t i = 0; i < 100; i++){ -            if ((this->peek16(E100_REG_I2C_CMD_STATUS) & I2C_ST_TIP) == 0) return; -            boost::this_thread::sleep(boost::posix_time::milliseconds(1)); -        } -        UHD_MSG(error) << "i2c_wait: timeout" << std::endl; -    } - -    bool wait_chk_ack(void){ -        i2c_wait(); -        return (this->peek16(E100_REG_I2C_CMD_STATUS) & I2C_ST_RXACK) == 0; -    } - -    void write_i2c(boost::uint8_t addr, const byte_vector_t &bytes){ -        poke16(E100_REG_I2C_DATA, (addr << 1) | 0); //addr and read bit (0) -        poke16(E100_REG_I2C_CMD_STATUS, I2C_CMD_WR | I2C_CMD_START | (bytes.size() == 0 ? I2C_CMD_STOP : 0)); - -        //wait for previous transfer to complete -        if(!wait_chk_ack()) { -            poke16(E100_REG_I2C_CMD_STATUS, I2C_CMD_STOP); -            return; -        } - -        for(size_t i = 0; i < bytes.size(); i++) { -            poke16(E100_REG_I2C_DATA, bytes[i]); -            poke16(E100_REG_I2C_CMD_STATUS, I2C_CMD_WR | ((i == (bytes.size() - 1)) ? I2C_CMD_STOP : 0)); -            if(!wait_chk_ack()) { -                poke16(E100_REG_I2C_CMD_STATUS, I2C_CMD_STOP); -                return; -            } -        } -    } - -    byte_vector_t read_i2c(boost::uint8_t addr, size_t num_bytes){ -        byte_vector_t bytes; -        if(num_bytes == 0) return bytes; - -        while (peek16(E100_REG_I2C_CMD_STATUS) & I2C_ST_BUSY); - -        poke16(E100_REG_I2C_DATA, (addr << 1) | 1); //addr and read bit (1) -        poke16(E100_REG_I2C_CMD_STATUS, I2C_CMD_WR | I2C_CMD_START); -        //wait for previous transfer to complete -        if(!wait_chk_ack()) { -            poke16(E100_REG_I2C_CMD_STATUS, I2C_CMD_STOP); -        } -        for(; num_bytes > 0; num_bytes--) { -            poke16(E100_REG_I2C_CMD_STATUS, I2C_CMD_RD | ((num_bytes == 1) ? (I2C_CMD_STOP | I2C_CMD_NACK) : 0)); -            i2c_wait(); -            boost::uint8_t readback = peek16(E100_REG_I2C_DATA) & 0xFF; -            bytes.push_back(readback); -        } -        return bytes; -    } - -    /******************************************************************* -     * SPI -     ******************************************************************/ -    void spi_wait(void) { -        for (size_t i = 0; i < 100; i++){ -            if ((this->peek16(E100_REG_SPI_CTRL) & SPI_CTRL_GO_BSY) == 0) return; -            boost::this_thread::sleep(boost::posix_time::milliseconds(1)); -        } -        UHD_MSG(error) << "spi_wait: timeout" << std::endl; -    } - -    boost::uint32_t transact_spi( -        int which_slave, -        const spi_config_t &config, -        boost::uint32_t bits, -        size_t num_bits, -        bool readback -    ){ -        if (which_slave == UE_SPI_SS_AD9522) return bitbang_spi( -            bits, num_bits, readback -        ); - -        UHD_ASSERT_THROW(num_bits <= 32 and (num_bits % 8) == 0); - -        int edge_flags = ((config.miso_edge==spi_config_t::EDGE_FALL) ? SPI_CTRL_RXNEG : 0) | -                         ((config.mosi_edge==spi_config_t::EDGE_FALL) ? 0 : SPI_CTRL_TXNEG) -                         ; -        boost::uint16_t ctrl = SPI_CTRL_ASS | (SPI_CTRL_CHAR_LEN_MASK & num_bits) | edge_flags; - -        spi_wait(); -        poke16(E100_REG_SPI_DIV, 0x0001); // = fpga_clk / 4 -        poke32(E100_REG_SPI_SS, which_slave & 0xFFFF); -        poke32(E100_REG_SPI_TXRX0, bits); -        poke16(E100_REG_SPI_CTRL, ctrl); -        poke16(E100_REG_SPI_CTRL, ctrl | SPI_CTRL_GO_BSY); - -        if (not readback) return 0; -        spi_wait(); -        return peek32(E100_REG_SPI_TXRX0); -    } - -    boost::uint32_t bitbang_spi( -        boost::uint32_t bits, size_t num_bits, bool readback -    ){ -        if (_gpios.get() == NULL) { //init on demand... -            _gpios = iface_gpios_type::sptr(new iface_gpios_type()); -        } - -        boost::uint32_t rb_bits = 0; -        _gpios->spi_sen_gpio(0); - -        for (size_t i = 0; i < num_bits; i++){ -            _gpios->spi_sclk_gpio(0); -            _gpios->spi_mosi_gpio((bits >> (num_bits-i-1)) & 0x1); -            boost::this_thread::sleep(boost::posix_time::microseconds(10)); -            if (readback) rb_bits = (rb_bits << 1) | _gpios->spi_miso_gpio(); -            _gpios->spi_sclk_gpio(1); -            boost::this_thread::sleep(boost::posix_time::microseconds(10)); -        } - -        _gpios->spi_sen_gpio(1); -        boost::this_thread::sleep(boost::posix_time::microseconds(100)); -        return rb_bits; -    } - -    /******************************************************************* -     * UART -     ******************************************************************/ -    void write_uart(boost::uint8_t, const std::string &) { -        throw uhd::not_implemented_error("Unhandled command write_uart()"); -    } - -    std::string read_uart(boost::uint8_t) { -        throw uhd::not_implemented_error("Unhandled command read_uart()"); -    } -  private:      int _node_fd; -    i2c_dev_iface _i2c_dev_iface;      boost::mutex _ioctl_mutex; -    iface_gpios_type::sptr _gpios;  };  /***********************************************************************   * Public Make Function   **********************************************************************/ -e100_iface::sptr e100_iface::make(void){ -    return sptr(new e100_iface_impl()); +e100_ctrl::sptr e100_ctrl::make(const std::string &node){ +    return sptr(new e100_ctrl_impl(node));  } diff --git a/host/lib/usrp/e100/e100_ctrl.hpp b/host/lib/usrp/e100/e100_ctrl.hpp new file mode 100644 index 000000000..8520ea595 --- /dev/null +++ b/host/lib/usrp/e100/e100_ctrl.hpp @@ -0,0 +1,45 @@ +// +// 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/types/serial.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> + +class e100_ctrl : boost::noncopyable, public wb_iface{ +public: +    typedef boost::shared_ptr<e100_ctrl> sptr; + +    //! Make a new controller for E100 +    static sptr make(const std::string &node); + +    //! Make an i2c iface for the i2c device node +    static uhd::i2c_iface::sptr make_dev_i2c_iface(const std::string &node); + +    //! Make an i2c iface for the i2c device node +    static uhd::spi_iface::sptr make_aux_spi_iface(void); + +    virtual void ioctl(int request, void *mem) = 0; + +    virtual int get_file_descriptor(void) = 0; + +}; + +#endif /* INCLUDED_B100_CTRL_HPP */ diff --git a/host/lib/usrp/e100/e100_iface.hpp b/host/lib/usrp/e100/e100_iface.hpp deleted file mode 100644 index a0135a468..000000000 --- a/host/lib/usrp/e100/e100_iface.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// -// Copyright 2010-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_E100_IFACE_HPP -#define INCLUDED_E100_IFACE_HPP - -#include <uhd/transport/udp_simple.hpp> -#include <uhd/usrp/mboard_eeprom.hpp> -#include <uhd/types/serial.hpp> -#include <boost/shared_ptr.hpp> -#include <boost/utility.hpp> -#include <boost/cstdint.hpp> -#include <uhd/usrp/mboard_iface.hpp> - -//////////////////////////////////////////////////////////////////////// -// I2C addresses -//////////////////////////////////////////////////////////////////////// -#define I2C_DEV_EEPROM  0x50 // 24LC02[45]:  7-bits 1010xxx -#define	I2C_ADDR_MBOARD (I2C_DEV_EEPROM | 0x0) -#define	I2C_ADDR_TX_DB  (I2C_DEV_EEPROM | 0x4) -#define	I2C_ADDR_RX_DB  (I2C_DEV_EEPROM | 0x5) -//////////////////////////////////////////////////////////////////////// - -/*! - * The usrp-e interface class: - * Provides a set of functions to implementation layer. - * Including spi, peek, poke, control... - */ -class e100_iface : boost::noncopyable, public uhd::usrp::mboard_iface{ -public: -    typedef boost::shared_ptr<e100_iface> sptr; - -    /*! -     * Make a new usrp-e interface with the control transport. -     * \return a new usrp-e interface object -     */ -    static sptr make(void); - -    //! TODO implement this for multiple hardwares revs in the future -    std::string get_cname(void){ -        return "USRP-E100"; -    } - -    /*! -     * Get the underlying file descriptor. -     * \return the file descriptor -     */ -    virtual int get_file_descriptor(void) = 0; - -    /*! -     * Open a device node into this iface. -     * \param node the device node name -     */ -    virtual void open(const std::string &node) = 0; - -    /*! -     * Close the open device node in this iface. -     */ -    virtual void close(void) = 0; - -    /*! -     * Perform an ioctl call on the device node file descriptor. -     * This will throw when the internal ioctl call fails. -     * \param request the control word -     * \param mem pointer to some memory -     */ -    virtual void ioctl(int request, void *mem) = 0; - -    //! Get the I2C interface for the I2C device node -    virtual uhd::i2c_iface &get_i2c_dev_iface(void) = 0; - -    //motherboard eeprom map structure -    uhd::usrp::mboard_eeprom_t mb_eeprom; -}; - -#endif /* INCLUDED_E100_IFACE_HPP */ diff --git a/host/lib/usrp/e100/e100_impl.cpp b/host/lib/usrp/e100/e100_impl.cpp index 96ac6548b..a86a75816 100644 --- a/host/lib/usrp/e100/e100_impl.cpp +++ b/host/lib/usrp/e100/e100_impl.cpp @@ -18,8 +18,6 @@  #include "e100_impl.hpp"  #include "e100_regs.hpp"  #include <uhd/utils/msg.hpp> -#include <uhd/usrp/device_props.hpp> -#include <uhd/usrp/mboard_props.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/static.hpp>  #include <uhd/utils/images.hpp> @@ -27,12 +25,21 @@  #include <boost/format.hpp>  #include <boost/filesystem.hpp>  #include <boost/functional/hash.hpp> +#include <boost/assign/list_of.hpp>  #include <fstream>  using namespace uhd;  using namespace uhd::usrp;  namespace fs = boost::filesystem; +//////////////////////////////////////////////////////////////////////// +// I2C addresses +//////////////////////////////////////////////////////////////////////// +#define I2C_DEV_EEPROM  0x50 // 24LC02[45]:  7-bits 1010xxx +#define	I2C_ADDR_MBOARD (I2C_DEV_EEPROM | 0x0) +#define	I2C_ADDR_TX_DB  (I2C_DEV_EEPROM | 0x4) +#define	I2C_ADDR_RX_DB  (I2C_DEV_EEPROM | 0x5) +  /***********************************************************************   * Discovery   **********************************************************************/ @@ -55,9 +62,10 @@ static device_addrs_t e100_find(const device_addr_t &hint){          new_addr["type"] = "e100";          new_addr["node"] = fs::system_complete(fs::path(hint["node"])).string();          try{ -            e100_iface::sptr iface = e100_iface::make(); -            new_addr["name"] = iface->mb_eeprom["name"]; -            new_addr["serial"] = iface->mb_eeprom["serial"]; +            i2c_iface::sptr i2c_iface = e100_ctrl::make_dev_i2c_iface(E100_I2C_DEV_NODE); +            const mboard_eeprom_t mb_eeprom(*i2c_iface, mboard_eeprom_t::MAP_E100); +            new_addr["name"] = mb_eeprom["name"]; +            new_addr["serial"] = mb_eeprom["serial"];          }          catch(const std::exception &e){              new_addr["name"] = ""; @@ -87,12 +95,23 @@ static size_t hash_fpga_file(const std::string &file_path){  }  static device::sptr e100_make(const device_addr_t &device_addr){ +    return device::sptr(new e100_impl(device_addr)); +} + +UHD_STATIC_BLOCK(register_e100_device){ +    device::register_device(&e100_find, &e100_make); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      //setup the main interface into fpga      const std::string node = device_addr["node"]; -    e100_iface::sptr iface = e100_iface::make(); +    _fpga_ctrl = e100_ctrl::make(node); -    //extract the fpga path for usrp-e and compute hash +    //extract the fpga path and compute hash      const std::string e100_fpga_image = find_image_path(device_addr.get("fpga", E100_FPGA_FILE_NAME));      const boost::uint32_t file_hash = boost::uint32_t(hash_fpga_file(e100_fpga_image)); @@ -100,23 +119,23 @@ static device::sptr e100_make(const device_addr_t &device_addr){      // - close the device node      // - load the fpga bin file      // - re-open the device node -    iface->open(node); //open here so we can do FPGA hash check -    if (iface->peek32(E100_REG_RB_MISC_TEST32) != file_hash){ -        iface->close(); +    if (_fpga_ctrl->peek32(E100_REG_RB_MISC_TEST32) != file_hash){ +        _fpga_ctrl.reset();          e100_load_fpga(e100_fpga_image); -        iface->open(node); +        _fpga_ctrl = e100_ctrl::make(node);      }      //setup clock control here to ensure that the FPGA has a good clock before we continue      const double master_clock_rate = device_addr.cast<double>("master_clock_rate", E100_DEFAULT_CLOCK_RATE); -    e100_clock_ctrl::sptr clock_ctrl = e100_clock_ctrl::make(iface, master_clock_rate); +    _aux_spi_iface = e100_ctrl::make_aux_spi_iface(); +    _clock_ctrl = e100_clock_ctrl::make(_aux_spi_iface, master_clock_rate);      //Perform wishbone readback tests, these tests also write the hash      bool test_fail = false;      UHD_MSG(status) << "Performing wishbone readback test... " << std::flush;      for (size_t i = 0; i < 100; i++){ -        iface->poke32(E100_REG_SR_MISC_TEST32, file_hash); -        test_fail = iface->peek32(E100_REG_RB_MISC_TEST32) != file_hash; +        _fpga_ctrl->poke32(E100_REG_SR_MISC_TEST32, file_hash); +        test_fail = _fpga_ctrl->peek32(E100_REG_RB_MISC_TEST32) != file_hash;          if (test_fail) break; //exit loop on any failure      }      UHD_MSG(status) << ((test_fail)? " fail" : "pass") << std::endl; @@ -128,7 +147,7 @@ static device::sptr e100_make(const device_addr_t &device_addr){      );      //check that the compatibility is correct -    const boost::uint16_t fpga_compat_num = iface->peek16(E100_REG_MISC_COMPAT); +    const boost::uint16_t fpga_compat_num = _fpga_ctrl->peek16(E100_REG_MISC_COMPAT);      if (fpga_compat_num != E100_FPGA_COMPAT_NUM){          throw uhd::runtime_error(str(boost::format(              "\nPlease update the FPGA image for your device.\n" @@ -138,91 +157,234 @@ static device::sptr e100_make(const device_addr_t &device_addr){          ) % E100_FPGA_COMPAT_NUM % fpga_compat_num));      } -    return device::sptr(new e100_impl(device_addr, iface, clock_ctrl)); -} +    //////////////////////////////////////////////////////////////////// +    // Create controller objects +    //////////////////////////////////////////////////////////////////// +    _fpga_i2c_ctrl = i2c_core_100::make(_fpga_ctrl, E100_REG_SLAVE(3)); +    _fpga_spi_ctrl = spi_core_100::make(_fpga_ctrl, E100_REG_SLAVE(2)); +    _dev_i2c_iface = e100_ctrl::make_dev_i2c_iface(E100_I2C_DEV_NODE); +    _data_transport = e100_make_mmap_zero_copy(_fpga_ctrl); + +    //////////////////////////////////////////////////////////////////// +    // Initialize the properties tree +    //////////////////////////////////////////////////////////////////// +    _tree = property_tree::make(); +    _tree->create<std::string>("/name").set("E-Series Device"); +    const property_tree::path_type mb_path = "/mboards/0"; +    _tree->create<std::string>(mb_path / "name").set("E100 (euewanee)"); + +    //////////////////////////////////////////////////////////////////// +    // setup the mboard eeprom +    //////////////////////////////////////////////////////////////////// +    const mboard_eeprom_t mb_eeprom(*_dev_i2c_iface, mboard_eeprom_t::MAP_E100); +    _tree->create<mboard_eeprom_t>(mb_path / "eeprom") +        .set(mb_eeprom) +        .subscribe(boost::bind(&e100_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(&e100_clock_ctrl::get_fpga_clock_rate, _clock_ctrl)) +        .subscribe(boost::bind(&e100_impl::update_tick_rate, this, _1)); + +    //////////////////////////////////////////////////////////////////// +    // create codec control objects +    //////////////////////////////////////////////////////////////////// +    _codec_ctrl = e100_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(e100_codec_ctrl::rx_pga_gain_range); +    _tree->create<double>(rx_codec_path / "gains/pga/value") +        .coerce(boost::bind(&e100_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(e100_codec_ctrl::tx_pga_gain_range); +    _tree->create<double>(tx_codec_path / "gains/pga/value") +        .subscribe(boost::bind(&e100_codec_ctrl::set_tx_pga_gain, _codec_ctrl, _1)) +        .publish(boost::bind(&e100_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, E100_REG_SR_ADDR(UE_SR_RX_FRONT)); +    _tx_fe = tx_frontend_core_200::make(_fpga_ctrl, E100_REG_SR_ADDR(UE_SR_TX_FRONT)); +    //TODO lots of properties to expose here for frontends +    _tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec") +        .subscribe(boost::bind(&e100_impl::update_rx_subdev_spec, this, _1)); +    _tree->create<subdev_spec_t>(mb_path / "tx_subdev_spec") +        .subscribe(boost::bind(&e100_impl::update_tx_subdev_spec, this, _1)); + +    //////////////////////////////////////////////////////////////////// +    // create rx dsp control objects +    //////////////////////////////////////////////////////////////////// +    _rx_dsps.push_back(rx_dsp_core_200::make( +        _fpga_ctrl, E100_REG_SR_ADDR(UE_SR_RX_DSP0), E100_REG_SR_ADDR(UE_SR_RX_CTRL0), E100_RX_SID_BASE + 0 +    )); +    _rx_dsps.push_back(rx_dsp_core_200::make( +        _fpga_ctrl, E100_REG_SR_ADDR(UE_SR_RX_DSP1), E100_REG_SR_ADDR(UE_SR_RX_CTRL1), E100_RX_SID_BASE + 1 +    )); +    for (size_t dspno = 0; dspno < _rx_dsps.size(); dspno++){ +        _rx_dsps[dspno]->set_link_rate(E100_LINK_RATE_BPS); +        _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(&e100_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)); +    } -UHD_STATIC_BLOCK(register_e100_device){ -    device::register_device(&e100_find, &e100_make); -} +    //////////////////////////////////////////////////////////////////// +    // create tx dsp control objects +    //////////////////////////////////////////////////////////////////// +    _tx_dsp = tx_dsp_core_200::make( +        _fpga_ctrl, E100_REG_SR_ADDR(UE_SR_TX_DSP), E100_REG_SR_ADDR(UE_SR_TX_CTRL), E100_TX_ASYNC_SID +    ); +    _tx_dsp->set_link_rate(E100_LINK_RATE_BPS); +    _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(&e100_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 = E100_REG_RB_TIME_NOW_SECS; +    time64_rb_bases.rb_ticks_now = E100_REG_RB_TIME_NOW_TICKS; +    time64_rb_bases.rb_secs_pps = E100_REG_RB_TIME_PPS_SECS; +    time64_rb_bases.rb_ticks_pps = E100_REG_RB_TIME_PPS_TICKS; +    _time64 = time64_core_200::make( +        _fpga_ctrl, E100_REG_SR_ADDR(UE_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 / "clock_source/value") +        .subscribe(boost::bind(&e100_impl::update_clock_source, this, _1)); +    static const std::vector<std::string> clock_sources = boost::assign::list_of("internal")("external")("auto"); +    _tree->create<std::vector<std::string> >(mb_path / "clock_source/options").set(clock_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_DB); +    tx_db_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_TX_DB); +    gdb_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_TX_DB ^ 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(&e100_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(&e100_impl::set_db_eeprom, this, "tx", _1)); +    _tree->create<dboard_eeprom_t>(mb_path / "dboards/A/gdb_eeprom") +        .set(gdb_eeprom) +        .subscribe(boost::bind(&e100_impl::set_db_eeprom, this, "gdb", _1)); + +    //create a new dboard interface and manager +    _dboard_iface = make_e100_dboard_iface(_fpga_ctrl, _fpga_i2c_ctrl, _fpga_spi_ctrl, _clock_ctrl, _codec_ctrl); +    _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) +        ); +    } -/*********************************************************************** - * Structors - **********************************************************************/ -e100_impl::e100_impl( -    const uhd::device_addr_t &device_addr, -    e100_iface::sptr iface, -    e100_clock_ctrl::sptr clock_ctrl -): -    _iface(iface), -    _clock_ctrl(clock_ctrl), -    _codec_ctrl(e100_codec_ctrl::make(_iface)), -    _data_transport(e100_make_mmap_zero_copy(_iface)), -    _recv_frame_size(std::min(_data_transport->get_recv_frame_size(), size_t(device_addr.cast<double>("recv_frame_size", 1e9)))), -    _send_frame_size(std::min(_data_transport->get_send_frame_size(), size_t(device_addr.cast<double>("send_frame_size", 1e9)))) -{ - -    //setup otw types -    _send_otw_type.width = 16; -    _send_otw_type.shift = 0; -    _send_otw_type.byteorder = otw_type_t::BO_LITTLE_ENDIAN; - -    _recv_otw_type.width = 16; -    _recv_otw_type.shift = 0; -    _recv_otw_type.byteorder = otw_type_t::BO_LITTLE_ENDIAN; - -    //initialize the mboard -    mboard_init(); - -    //initialize the dboards -    dboard_init(); - -    //initialize the dsps -    dsp_init(); - -    //init the codec properties -    codec_init(); - -    //set default subdev specs -    this->mboard_set(MBOARD_PROP_RX_SUBDEV_SPEC, subdev_spec_t()); -    this->mboard_set(MBOARD_PROP_TX_SUBDEV_SPEC, subdev_spec_t()); - -    //init the io send/recv -    io_init(); +    //initialize io handling +    this->io_init(); + +    //////////////////////////////////////////////////////////////////// +    // do some post-init tasks +    //////////////////////////////////////////////////////////////////// +    _tree->access<double>(mb_path / "tick_rate").update() //update and then subscribe the clock callback +        .subscribe(boost::bind(&e100_clock_ctrl::set_fpga_clock_rate, _clock_ctrl, _1)); + +    //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); +    } + +    _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 / "clock_source/value").set("internal"); +    _tree->access<std::string>(mb_path / "time_source/value").set("none");  }  e100_impl::~e100_impl(void){ -    _io_impl.reset(); //reset here, seems to fix hang? +    /* NOP */  } -/*********************************************************************** - * Device Get - **********************************************************************/ -void e100_impl::get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<device_prop_t>()){ -    case DEVICE_PROP_NAME: -        val = std::string("usrp-e device"); -        return; - -    case DEVICE_PROP_MBOARD: -        UHD_ASSERT_THROW(key.name == ""); -        val = _mboard_proxy->get_link(); -        return; +double e100_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'); +} -    case DEVICE_PROP_MBOARD_NAMES: -        val = prop_names_t(1, ""); //vector of size 1 with empty string -        return; +void e100_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){ +    mb_eeprom.commit(*_dev_i2c_iface, mboard_eeprom_t::MAP_E100); +} -    default: UHD_THROW_PROP_GET_ERROR(); -    } +void e100_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_DB); +    if (type == "tx") db_eeprom.store(*_fpga_i2c_ctrl, I2C_ADDR_TX_DB); +    if (type == "gdb") db_eeprom.store(*_fpga_i2c_ctrl, I2C_ADDR_TX_DB ^ 5);  } -/*********************************************************************** - * Device Set - **********************************************************************/ -void e100_impl::set(const wax::obj &, const wax::obj &){ -    UHD_THROW_PROP_SET_ERROR(); +void e100_impl::update_clock_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 == "external") _clock_ctrl->use_external_ref(); +    else throw uhd::runtime_error("unhandled clock configuration reference source: " + source);  } diff --git a/host/lib/usrp/e100/e100_impl.hpp b/host/lib/usrp/e100/e100_impl.hpp index c7751acf9..e24360223 100644 --- a/host/lib/usrp/e100/e100_impl.hpp +++ b/host/lib/usrp/e100/e100_impl.hpp @@ -15,13 +15,22 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include "e100_iface.hpp" +#include "e100_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/usrp/subdev_spec.hpp>  #include <uhd/usrp/dboard_eeprom.hpp> +#include <uhd/usrp/mboard_eeprom.hpp>  #include <uhd/types/otw_type.hpp>  #include <uhd/types/clock_config.hpp>  #include <uhd/types/stream_cmd.hpp> @@ -31,56 +40,29 @@  #ifndef INCLUDED_E100_IMPL_HPP  #define INCLUDED_E100_IMPL_HPP -uhd::transport::zero_copy_if::sptr e100_make_mmap_zero_copy(e100_iface::sptr iface); +uhd::transport::zero_copy_if::sptr e100_make_mmap_zero_copy(e100_ctrl::sptr iface); +static const double          E100_LINK_RATE_BPS = 256e6/8; +static const std::string     E100_I2C_DEV_NODE = "/dev/i2c-3";  static const std::string     E100_FPGA_FILE_NAME = "usrp_e100_fpga_v2.bin";  static const boost::uint16_t E100_FPGA_COMPAT_NUM = 0x05; +static const boost::uint32_t E100_RX_SID_BASE = 2; +static const boost::uint32_t E100_TX_ASYNC_SID = 1;  static const double          E100_DEFAULT_CLOCK_RATE = 64e6; -static const size_t          E100_NUM_RX_DSPS = 2; -static const size_t          E100_NUM_TX_DSPS = 1; -static const boost::uint32_t E100_DSP_SID_BASE = 2; //leave room for other dsp (increments by 1) -static const boost::uint32_t E100_ASYNC_SID = 1;  //! load an fpga image from a bin file into the usrp-e fpga  extern void e100_load_fpga(const std::string &bin_file); -/*! - * Make a usrp-e dboard interface. - * \param iface the usrp-e interface object - * \param clock the clock control interface - * \param codec the codec control interface - * \return a sptr to a new dboard interface - */ -uhd::usrp::dboard_iface::sptr make_usrp_e100_dboard_iface( -    e100_iface::sptr iface, +//! Make an e100 dboard interface +uhd::usrp::dboard_iface::sptr make_e100_dboard_iface( +    wb_iface::sptr wb_iface, +    uhd::i2c_iface::sptr i2c_iface, +    uhd::spi_iface::sptr spi_iface,      e100_clock_ctrl::sptr clock,      e100_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);} -}; - -/*!   * USRP-E100 implementation guts:   * The implementation details are encapsulated here.   * Handles properties on the mboard, dboard, dsps... @@ -88,11 +70,7 @@ private:  class e100_impl : public uhd::device{  public:      //structors -    e100_impl( -        const uhd::device_addr_t &, -        e100_iface::sptr, -        e100_clock_ctrl::sptr -    ); +    e100_impl(const uhd::device_addr_t &);      ~e100_impl(void);      //the io interface @@ -103,82 +81,49 @@ public:      size_t get_max_recv_samps_per_packet(void) const;  private: -    //interface to ioctls and file descriptor -    e100_iface::sptr _iface; - -    //ad9522 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;      e100_clock_ctrl::sptr _clock_ctrl; - -    //ad9862 codec control      e100_codec_ctrl::sptr _codec_ctrl; +    e100_ctrl::sptr _fpga_ctrl; +    uhd::i2c_iface::sptr _dev_i2c_iface; +    uhd::spi_iface::sptr _aux_spi_iface; -    //handle io stuff +    //transports      uhd::transport::zero_copy_if::sptr _data_transport; -    UHD_PIMPL_DECL(io_impl) _io_impl; -    size_t _recv_frame_size, _send_frame_size; -    uhd::otw_type_t _send_otw_type, _recv_otw_type; -    void io_init(void); -    void handle_irq(void); -    void handle_overrun(size_t); -    void update_xport_channel_mapping(void); - -    //configuration shadows -    uhd::clock_config_t _clock_config; - -    //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 &); -    wax_obj_proxy::sptr _mboard_proxy; -    uhd::usrp::subdev_spec_t _rx_subdev_spec, _tx_subdev_spec; - -    //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; - -    //codec functions and settings -    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; -     -    //clock control functions and settings -    void init_clock_config(void); -    void update_clock_config(void); +    //handle io stuff +    uhd::otw_type_t _rx_otw_type, _tx_otw_type; +    UHD_PIMPL_DECL(io_impl) _io_impl; +    void io_init(void); + +    //device properties interface +    void get(const wax::obj &, wax::obj &val){ +        val = _tree; //entry point into property tree +    } + +    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_clock_source(const std::string &); +  };  #endif /* INCLUDED_E100_IMPL_HPP */ diff --git a/host/lib/usrp/e100/e100_mmap_zero_copy.cpp b/host/lib/usrp/e100/e100_mmap_zero_copy.cpp index 5370b7594..cdb7094f4 100644 --- a/host/lib/usrp/e100/e100_mmap_zero_copy.cpp +++ b/host/lib/usrp/e100/e100_mmap_zero_copy.cpp @@ -15,7 +15,7 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include "e100_iface.hpp" +#include "e100_ctrl.hpp"  #include <uhd/transport/zero_copy.hpp>  #include <uhd/utils/log.hpp>  #include <uhd/exception.hpp> @@ -104,7 +104,7 @@ private:   **********************************************************************/  class e100_mmap_zero_copy_impl : public zero_copy_if{  public: -    e100_mmap_zero_copy_impl(e100_iface::sptr iface): +    e100_mmap_zero_copy_impl(e100_ctrl::sptr iface):          _fd(iface->get_file_descriptor()), _recv_index(0), _send_index(0)      {          //get system sizes @@ -264,6 +264,6 @@ private:  /***********************************************************************   * The zero copy interface make function   **********************************************************************/ -zero_copy_if::sptr e100_make_mmap_zero_copy(e100_iface::sptr iface){ +zero_copy_if::sptr e100_make_mmap_zero_copy(e100_ctrl::sptr iface){      return zero_copy_if::sptr(new e100_mmap_zero_copy_impl(iface));  } diff --git a/host/lib/usrp/e100/e100_regs.hpp b/host/lib/usrp/e100/e100_regs.hpp index d5e61f45f..28ef707dc 100644 --- a/host/lib/usrp/e100/e100_regs.hpp +++ b/host/lib/usrp/e100/e100_regs.hpp @@ -50,13 +50,6 @@  //these are 32-bit registers mapped onto the 16-bit Wishbone bus.  //Using peek32/poke32 should allow transparent use of these registers.  #define E100_REG_SPI_BASE E100_REG_SLAVE(2) -#define E100_REG_SPI_TXRX0 E100_REG_SPI_BASE + 0 -#define E100_REG_SPI_TXRX1 E100_REG_SPI_BASE + 4 -#define E100_REG_SPI_TXRX2 E100_REG_SPI_BASE + 8 -#define E100_REG_SPI_TXRX3 E100_REG_SPI_BASE + 12 -#define E100_REG_SPI_CTRL  E100_REG_SPI_BASE + 16 -#define E100_REG_SPI_DIV   E100_REG_SPI_BASE + 20 -#define E100_REG_SPI_SS    E100_REG_SPI_BASE + 24  //spi slave constants  #define UE_SPI_SS_AD9522    (1 << 3) @@ -64,51 +57,10 @@  #define UE_SPI_SS_TX_DB     (1 << 1)  #define UE_SPI_SS_RX_DB     (1 << 0) -//spi ctrl register bit definitions -#define SPI_CTRL_ASS      (1<<13) -#define SPI_CTRL_IE       (1<<12) -#define SPI_CTRL_LSB      (1<<11) -#define SPI_CTRL_TXNEG    (1<<10) //mosi edge, push on falling edge when 1 -#define SPI_CTRL_RXNEG    (1<< 9) //miso edge, latch on falling edge when 1 -#define SPI_CTRL_GO_BSY   (1<< 8) -#define SPI_CTRL_CHAR_LEN_MASK 0x7F -  ////////////////////////////////////////////////  // Slave 3 -- I2C Core  #define E100_REG_I2C_BASE E100_REG_SLAVE(3) -#define E100_REG_I2C_PRESCALER_LO E100_REG_I2C_BASE + 0 -#define E100_REG_I2C_PRESCALER_HI E100_REG_I2C_BASE + 2 -#define E100_REG_I2C_CTRL         E100_REG_I2C_BASE + 4 -#define E100_REG_I2C_DATA         E100_REG_I2C_BASE + 6 -#define E100_REG_I2C_CMD_STATUS   E100_REG_I2C_BASE + 8 - -//and while we're here... - -// -// STA, STO, RD, WR, and IACK bits are cleared automatically -// - -#define	I2C_CTRL_EN	(1 << 7)	// core enable -#define	I2C_CTRL_IE	(1 << 6)	// interrupt enable - -#define	I2C_CMD_START	(1 << 7)	// generate (repeated) start condition -#define I2C_CMD_STOP	(1 << 6)	// generate stop condition -#define	I2C_CMD_RD	(1 << 5)	// read from slave -#define I2C_CMD_WR	(1 << 4)	// write to slave -#define	I2C_CMD_NACK	(1 << 3)	// when a rcvr, send ACK (ACK=0) or NACK (ACK=1) -#define I2C_CMD_RSVD_2	(1 << 2)	// reserved -#define	I2C_CMD_RSVD_1	(1 << 1)	// reserved -#define I2C_CMD_IACK	(1 << 0)	// set to clear pending interrupt - -#define I2C_ST_RXACK	(1 << 7)	// Received acknowledgement from slave (1 = NAK, 0 = ACK) -#define	I2C_ST_BUSY	(1 << 6)	// 1 after START signal detected; 0 after STOP signal detected -#define	I2C_ST_AL	(1 << 5)	// Arbitration lost.  1 when core lost arbitration -#define	I2C_ST_RSVD_4	(1 << 4)	// reserved -#define	I2C_ST_RSVD_3	(1 << 3)	// reserved -#define	I2C_ST_RSVD_2	(1 << 2)	// reserved -#define I2C_ST_TIP	(1 << 1)	// Transfer-in-progress -#define	I2C_ST_IP	(1 << 0)	// Interrupt pending  ////////////////////////////////////////////////  // Slave 5 -- Error messages buffer @@ -201,94 +153,5 @@  #define E100_REG_CLEAR_TX           E100_REG_SR_ADDR(UE_SR_CLEAR_RX_FIFO)  #define E100_REG_GLOBAL_RESET       E100_REG_SR_ADDR(UE_SR_GLOBAL_RESET) -///////////////////////////////////////////////// -// DSP RX Regs -//////////////////////////////////////////////// -#define E100_REG_DSP_RX_HELPER(which, offset) ((which == 0)? \ -    (E100_REG_SR_ADDR(UE_SR_RX_DSP0 + offset)) : \ -    (E100_REG_SR_ADDR(UE_SR_RX_DSP1 + offset))) - -#define E100_REG_DSP_RX_FREQ(which)       E100_REG_DSP_RX_HELPER(which, 0) -#define E100_REG_DSP_RX_DECIM(which)      E100_REG_DSP_RX_HELPER(which, 2) -#define E100_REG_DSP_RX_MUX(which)        E100_REG_DSP_RX_HELPER(which, 3) - -#define E100_FLAG_DSP_RX_MUX_SWAP_IQ   (1 << 0) -#define E100_FLAG_DSP_RX_MUX_REAL_MODE (1 << 1) - -/////////////////////////////////////////////////// -// RX CTRL regs -/////////////////////////////////////////////////// -#define E100_REG_RX_CTRL_HELPER(which, offset) ((which == 0)? \ -    (E100_REG_SR_ADDR(UE_SR_RX_CTRL0 + offset)) : \ -    (E100_REG_SR_ADDR(UE_SR_RX_CTRL1 + offset))) - -#define E100_REG_RX_CTRL_STREAM_CMD(which)     E100_REG_RX_CTRL_HELPER(which, 0) -#define E100_REG_RX_CTRL_TIME_SECS(which)      E100_REG_RX_CTRL_HELPER(which, 1) -#define E100_REG_RX_CTRL_TIME_TICKS(which)     E100_REG_RX_CTRL_HELPER(which, 2) -#define E100_REG_RX_CTRL_CLEAR(which)          E100_REG_RX_CTRL_HELPER(which, 3) -#define E100_REG_RX_CTRL_VRT_HDR(which)        E100_REG_RX_CTRL_HELPER(which, 4) -#define E100_REG_RX_CTRL_VRT_SID(which)        E100_REG_RX_CTRL_HELPER(which, 5) -#define E100_REG_RX_CTRL_VRT_TLR(which)        E100_REG_RX_CTRL_HELPER(which, 6) -#define E100_REG_RX_CTRL_NSAMPS_PP(which)      E100_REG_RX_CTRL_HELPER(which, 7) -#define E100_REG_RX_CTRL_NCHANNELS(which)      E100_REG_RX_CTRL_HELPER(which, 8) - -///////////////////////////////////////////////// -// RX FE -//////////////////////////////////////////////// -#define E100_REG_RX_FE_SWAP_IQ             E100_REG_SR_ADDR(UE_SR_RX_FRONT + 0) //lower bit -#define E100_REG_RX_FE_MAG_CORRECTION      E100_REG_SR_ADDR(UE_SR_RX_FRONT + 1) //18 bits -#define E100_REG_RX_FE_PHASE_CORRECTION    E100_REG_SR_ADDR(UE_SR_RX_FRONT + 2) //18 bits -#define E100_REG_RX_FE_OFFSET_I            E100_REG_SR_ADDR(UE_SR_RX_FRONT + 3) //18 bits -#define E100_REG_RX_FE_OFFSET_Q            E100_REG_SR_ADDR(UE_SR_RX_FRONT + 4) //18 bits - -///////////////////////////////////////////////// -// DSP TX Regs -//////////////////////////////////////////////// -#define E100_REG_DSP_TX_FREQ          E100_REG_SR_ADDR(UE_SR_TX_DSP + 0) -#define E100_REG_DSP_TX_SCALE_IQ      E100_REG_SR_ADDR(UE_SR_TX_DSP + 1) -#define E100_REG_DSP_TX_INTERP_RATE   E100_REG_SR_ADDR(UE_SR_TX_DSP + 2) - -/////////////////////////////////////////////////// -// TX CTRL regs -/////////////////////////////////////////////////// -#define E100_REG_TX_CTRL_NUM_CHAN       E100_REG_SR_ADDR(UE_SR_TX_CTRL + 0) -#define E100_REG_TX_CTRL_CLEAR_STATE    E100_REG_SR_ADDR(UE_SR_TX_CTRL + 1) -#define E100_REG_TX_CTRL_REPORT_SID     E100_REG_SR_ADDR(UE_SR_TX_CTRL + 2) -#define E100_REG_TX_CTRL_POLICY         E100_REG_SR_ADDR(UE_SR_TX_CTRL + 3) -#define E100_REG_TX_CTRL_CYCLES_PER_UP  E100_REG_SR_ADDR(UE_SR_TX_CTRL + 4) -#define E100_REG_TX_CTRL_PACKETS_PER_UP E100_REG_SR_ADDR(UE_SR_TX_CTRL + 5) - -#define E100_FLAG_TX_CTRL_POLICY_WAIT          (0x1 << 0) -#define E100_FLAG_TX_CTRL_POLICY_NEXT_PACKET   (0x1 << 1) -#define E100_FLAG_TX_CTRL_POLICY_NEXT_BURST    (0x1 << 2) - -///////////////////////////////////////////////// -// TX FE -//////////////////////////////////////////////// -#define E100_REG_TX_FE_DC_OFFSET_I         E100_REG_SR_ADDR(UE_SR_TX_FRONT + 0) //24 bits -#define E100_REG_TX_FE_DC_OFFSET_Q         E100_REG_SR_ADDR(UE_SR_TX_FRONT + 1) //24 bits -#define E100_REG_TX_FE_MAC_CORRECTION      E100_REG_SR_ADDR(UE_SR_TX_FRONT + 2) //18 bits -#define E100_REG_TX_FE_PHASE_CORRECTION    E100_REG_SR_ADDR(UE_SR_TX_FRONT + 3) //18 bits -#define E100_REG_TX_FE_MUX                 E100_REG_SR_ADDR(UE_SR_TX_FRONT + 4) //8 bits (std output = 0x10, reversed = 0x01) - -///////////////////////////////////////////////// -// VITA49 64 bit time (write only) -//////////////////////////////////////////////// -#define E100_REG_TIME64_SECS      E100_REG_SR_ADDR(UE_SR_TIME64 + 0) -#define E100_REG_TIME64_TICKS     E100_REG_SR_ADDR(UE_SR_TIME64 + 1) -#define E100_REG_TIME64_FLAGS     E100_REG_SR_ADDR(UE_SR_TIME64 + 2) -#define E100_REG_TIME64_IMM       E100_REG_SR_ADDR(UE_SR_TIME64 + 3) -#define E100_REG_TIME64_TPS       E100_REG_SR_ADDR(UE_SR_TIME64 + 4) -#define E100_REG_TIME64_MIMO_SYNC E100_REG_SR_ADDR(UE_SR_TIME64 + 5) - -//pps flags (see above) -#define E100_FLAG_TIME64_PPS_NEGEDGE (0 << 0) -#define E100_FLAG_TIME64_PPS_POSEDGE (1 << 0) -#define E100_FLAG_TIME64_PPS_SMA     (0 << 1) -#define E100_FLAG_TIME64_PPS_MIMO    (1 << 1) - -#define E100_FLAG_TIME64_LATCH_NOW 1 -#define E100_FLAG_TIME64_LATCH_NEXT_PPS 0 -  #endif diff --git a/host/lib/usrp/e100/io_impl.cpp b/host/lib/usrp/e100/io_impl.cpp index 65fb1f3db..9f7dc9921 100644 --- a/host/lib/usrp/e100/io_impl.cpp +++ b/host/lib/usrp/e100/io_impl.cpp @@ -15,6 +15,8 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // +#include "recv_packet_demuxer.hpp" +#include "validate_subdev_spec.hpp"  #include "../../transport/super_recv_packet_handler.hpp"  #include "../../transport/super_send_packet_handler.hpp"  #include <linux/usrp_e.h> //ioctl structures and constants @@ -22,8 +24,6 @@  #include "e100_regs.hpp"  #include <uhd/utils/msg.hpp>  #include <uhd/utils/log.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> @@ -47,64 +47,31 @@ using namespace uhd::transport;   * - vrt packet handler states   **********************************************************************/  struct e100_impl::io_impl{ -    io_impl(zero_copy_if::sptr &xport): -        data_transport(xport), -        async_msg_fifo(100/*messages deep*/) -    { -        for (size_t i = 0; i < E100_NUM_RX_DSPS; 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())); -        } -    } +    io_impl(void): +        false_alarm(0), async_msg_fifo(100/*messages deep*/) +    { /* NOP */ }      ~io_impl(void){          recv_pirate_crew.interrupt_all();          recv_pirate_crew.join_all(); -        for (size_t i = 0; i < _buffs_queue.size(); i++){ -            delete _buffs_queue[i]; -        } -    } - -    std::vector<bounded_buffer<managed_recv_buffer::sptr> *> _buffs_queue; - -    //gets buffer, determines if its the requested index, -    //and either queues the buffer or returns the buffer -    managed_recv_buffer::sptr get_recv_buff(const size_t index, const double timeout){ -        while (true){ -            managed_recv_buffer::sptr buff; - -            //attempt to pop a buffer from the queue -            if (_buffs_queue[index]->pop_with_haste(buff)) return buff; - -            //otherwise, call into the transport -            buff = data_transport->get_recv_buff(timeout); -            if (buff.get() == NULL) return buff; //timeout - -            //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]) - E100_DSP_SID_BASE; -            if (rx_index == index) return buff; //got expected message - -            //otherwise queue and try again -            if (rx_index < E100_NUM_RX_DSPS) _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; -        }      } +    double tick_rate; //set by update tick rate method +    e100_ctrl::sptr iface; //so handle irq can peek and poke +    void handle_irq(void); +    size_t false_alarm;      //The data transport is listed first so that it is deconstructed last,      //which is after the states and booty which may hold managed buffers. -    zero_copy_if::sptr data_transport; +    recv_packet_demuxer::sptr demuxer;      //state management for the vrt packet handler code      sph::recv_packet_handler recv_handler;      sph::send_packet_handler send_handler; -    bool continuous_streaming;      //a pirate's life is the life for me!      void recv_pirate_loop(          boost::barrier &spawn_barrier, -        const boost::function<void(void)> &handle, -        e100_iface::sptr //keep a sptr to iface which shares gpio147 +        spi_iface::sptr //keep a sptr to iface which shares gpio147      ){          spawn_barrier.wait(); @@ -120,7 +87,7 @@ struct e100_impl::io_impl{              pfd.fd = fd;              pfd.events = POLLPRI | POLLERR;              ssize_t ret = ::poll(&pfd, 1, 100/*ms*/); -            if (ret > 0) handle(); +            if (ret > 0) this->handle_irq();          }          //cleanup before thread exit @@ -130,48 +97,25 @@ struct e100_impl::io_impl{      boost::thread_group recv_pirate_crew;  }; -/*********************************************************************** - * Helper Functions - **********************************************************************/ -void e100_impl::io_init(void){ - -    //setup before the registers (transport called to calculate max spp) -    _io_impl = UHD_PIMPL_MAKE(io_impl, (_data_transport)); - -    //clear state machines -    _iface->poke32(E100_REG_CLEAR_RX, 0); -    _iface->poke32(E100_REG_CLEAR_TX, 0); - -    //prepare the async msg buffer for incoming messages -    _iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 0); //clear -    while ((_iface->peek32(E100_REG_RB_ERR_STATUS) & (1 << 2)) == 0){} //wait for idle -    _iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 1); //start - -    //spawn a pirate, yarrr! -    boost::barrier spawn_barrier(2); -    boost::function<void(void)> handle_irq_cb = boost::bind(&e100_impl::handle_irq, this); -    _io_impl->recv_pirate_crew.create_thread(boost::bind( -        &e100_impl::io_impl::recv_pirate_loop, _io_impl.get(), -        boost::ref(spawn_barrier), handle_irq_cb, _iface -    )); -    spawn_barrier.wait(); -    //update mapping here since it didnt b4 when io init not called first -    update_xport_channel_mapping(); -} - -void e100_impl::handle_irq(void){ +void e100_impl::io_impl::handle_irq(void){      //check the status of the async msg buffer -    const boost::uint32_t status = _iface->peek32(E100_REG_RB_ERR_STATUS); -    if ((status & 0x3) == 0) return; //not done or error +    const boost::uint32_t status = iface->peek32(E100_REG_RB_ERR_STATUS); +    if ((status & 0x3) == 0){ //not done or error +        //This could be a false-alarm because spi readback is mixed in. +        //So we just sleep for a bit rather than interrupt continuously. +        if (false_alarm++ > 3) boost::this_thread::sleep(boost::posix_time::milliseconds(1)); +        return; +    } +    false_alarm = 0; //its a real message, reset the count...      //std::cout << boost::format("status: 0x%x") % status << std::endl;      //load the data struct and call the ioctl      usrp_e_ctl32 data;      data.offset = E100_REG_ERR_BUFF;      data.count = status >> 16; -    //FIXME ioctl reads words32 incorrectly _iface->ioctl(USRP_E_READ_CTL32, &data); +    //FIXME ioctl reads words32 incorrectly _fpga_ctrl->ioctl(USRP_E_READ_CTL32, &data);      for (size_t i = 0; i < data.count; i++){ -        data.buf[i] = _iface->peek32(E100_REG_ERR_BUFF + i*sizeof(boost::uint32_t)); +        data.buf[i] = iface->peek32(E100_REG_ERR_BUFF + i*sizeof(boost::uint32_t));          //std::cout << boost::format("    buff[%u] = 0x%08x\n") % i % data.buf[i];      } @@ -185,19 +129,19 @@ void e100_impl::handle_irq(void){      }      //handle a tx async report message -    if (if_packet_info.sid == E100_ASYNC_SID and if_packet_info.packet_type != vrt::if_packet_info_t::PACKET_TYPE_DATA){ +    if (if_packet_info.sid == E100_TX_ASYNC_SID and if_packet_info.packet_type != vrt::if_packet_info_t::PACKET_TYPE_DATA){          //fill in the async metadata          async_metadata_t metadata;          metadata.channel = 0;          metadata.has_time_spec = if_packet_info.has_tsi and if_packet_info.has_tsf;          metadata.time_spec = time_spec_t( -            time_t(if_packet_info.tsi), long(if_packet_info.tsf), _clock_ctrl->get_fpga_clock_rate() +            time_t(if_packet_info.tsi), long(if_packet_info.tsf), tick_rate          );          metadata.event_code = async_metadata_t::event_code_t(sph::get_context_code(data.buf, if_packet_info));          //push the message onto the queue -        _io_impl->async_msg_fifo.push_with_pop_on_full(metadata); +        async_msg_fifo.push_with_pop_on_full(metadata);          //print some fastpath messages          if (metadata.event_code & @@ -212,57 +156,122 @@ void e100_impl::handle_irq(void){      //prepare for the next round      prepare: -    _iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 0); //clear -    while ((_iface->peek32(E100_REG_RB_ERR_STATUS) & (1 << 2)) == 0){} //wait for idle -    _iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 1); //start +    iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 0); //clear +    while ((iface->peek32(E100_REG_RB_ERR_STATUS) & (1 << 2)) == 0){} //wait for idle +    iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 1); //start  } -void e100_impl::update_xport_channel_mapping(void){ -    if (_io_impl.get() == NULL) return; //not inited yet +/*********************************************************************** + * Helper Functions + **********************************************************************/ +void e100_impl::io_init(void){ -    //set all of the relevant properties on the handler -    boost::mutex::scoped_lock recv_lock = _io_impl->recv_handler.get_scoped_lock(); -    _io_impl->recv_handler.resize(_rx_subdev_spec.size()); +    //setup rx otw type +    _rx_otw_type.width = 16; +    _rx_otw_type.shift = 0; +    _rx_otw_type.byteorder = uhd::otw_type_t::BO_LITTLE_ENDIAN; + +    //setup tx otw type +    _tx_otw_type.width = 16; +    _tx_otw_type.shift = 0; +    _tx_otw_type.byteorder = uhd::otw_type_t::BO_LITTLE_ENDIAN; + +    //create new io impl +    _io_impl = UHD_PIMPL_MAKE(io_impl, ()); +    _io_impl->demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), E100_RX_SID_BASE); +    _io_impl->iface = _fpga_ctrl; + +    //clear state machines +    _fpga_ctrl->poke32(E100_REG_CLEAR_RX, 0); +    _fpga_ctrl->poke32(E100_REG_CLEAR_TX, 0); + +    //prepare the async msg buffer for incoming messages +    _fpga_ctrl->poke32(E100_REG_SR_ERR_CTRL, 1 << 0); //clear +    while ((_fpga_ctrl->peek32(E100_REG_RB_ERR_STATUS) & (1 << 2)) == 0){} //wait for idle +    _fpga_ctrl->poke32(E100_REG_SR_ERR_CTRL, 1 << 1); //start + +    //spawn a pirate, yarrr! +    boost::barrier spawn_barrier(2); +    _io_impl->recv_pirate_crew.create_thread(boost::bind( +        &e100_impl::io_impl::recv_pirate_loop, _io_impl.get(), +        boost::ref(spawn_barrier), _aux_spi_iface +    )); +    spawn_barrier.wait(); + +    //init some handler stuff      _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( -            &e100_impl::io_impl::get_recv_buff, _io_impl.get(), chan, _1 -        )); -        _io_impl->recv_handler.set_overflow_handler(chan, boost::bind( -            &e100_impl::handle_overrun, this, chan -        )); -    } -    _io_impl->recv_handler.set_converter(_recv_otw_type); +    _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()); +} -    //set all of the relevant properties on the handler +void e100_impl::update_tick_rate(const double rate){ +    _io_impl->tick_rate = rate; +    boost::mutex::scoped_lock recv_lock = _io_impl->recv_handler.get_scoped_lock(); +    _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.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 +    _io_impl->send_handler.set_tick_rate(rate); +} + +void e100_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 e100_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 e100_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 +    validate_subdev_spec(_tree, spec, "rx"); + +    //setup mux for this spec +    bool fe_swapped = false; +    for (size_t i = 0; i < spec.size(); i++){ +        const std::string conn = _tree->access<std::string>(root / spec[i].db_name / "rx_frontends" / spec[i].sd_name / "connection").get(); +        if (i == 0 and (conn == "QI" or conn == "Q")) fe_swapped = true; +        _rx_dsps[i]->set_mux(conn, fe_swapped); +    } +    _rx_fe->set_mux(fe_swapped); + +    //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( +            &recv_packet_demuxer::get_recv_buff, _io_impl->demuxer, i, _1          )); +        _io_impl->recv_handler.set_overflow_handler(i, boost::bind(&rx_dsp_core_200::handle_overflow, _rx_dsps[i]));      } -    _io_impl->send_handler.set_converter(_send_otw_type); -    _io_impl->send_handler.set_max_samples_per_packet(get_max_send_samps_per_packet());  } -void e100_impl::issue_ddc_stream_cmd(const stream_cmd_t &stream_cmd, const size_t index){ -    _io_impl->continuous_streaming = (stream_cmd.stream_mode == stream_cmd_t::STREAM_MODE_START_CONTINUOUS); -    _iface->poke32(E100_REG_RX_CTRL_STREAM_CMD(index), dsp_type1::calc_stream_cmd_word(stream_cmd)); -    _iface->poke32(E100_REG_RX_CTRL_TIME_SECS(index),  boost::uint32_t(stream_cmd.time_spec.get_full_secs())); -    _iface->poke32(E100_REG_RX_CTRL_TIME_TICKS(index), stream_cmd.time_spec.get_tick_count(_clock_ctrl->get_fpga_clock_rate())); -} +void e100_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(); +    property_tree::path_type root = "/mboards/0/dboards"; -void e100_impl::handle_overrun(const size_t index){ -    if (_io_impl->continuous_streaming){ -        this->issue_ddc_stream_cmd(stream_cmd_t::STREAM_MODE_START_CONTINUOUS, index); +    //sanity checking +    validate_subdev_spec(_tree, spec, "tx"); + +    //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->send_handler.set_xport_chan_get_buff(i, boost::bind( +            &zero_copy_if::get_send_buff, _data_transport, _1 +        ));      }  } @@ -274,8 +283,8 @@ size_t e100_impl::get_max_send_samps_per_packet(void) const{          + vrt::max_if_hdr_words32*sizeof(boost::uint32_t)          - sizeof(vrt::if_packet_info_t().cid) //no class id ever used      ; -    size_t bpp = _send_frame_size - hdr_size; -    return bpp/_send_otw_type.get_sample_size(); +    size_t bpp = _data_transport->get_send_frame_size() - hdr_size; +    return bpp/_tx_otw_type.get_sample_size();  }  size_t e100_impl::send( @@ -299,8 +308,8 @@ size_t e100_impl::get_max_recv_samps_per_packet(void) const{          + sizeof(vrt::if_packet_info_t().tlr) //forced to have trailer          - sizeof(vrt::if_packet_info_t().cid) //no class id ever used      ; -    size_t bpp = _recv_frame_size - hdr_size; -    return bpp/_recv_otw_type.get_sample_size(); +    size_t bpp = _data_transport->get_recv_frame_size() - hdr_size; +    return bpp/_rx_otw_type.get_sample_size();  }  size_t e100_impl::recv( diff --git a/host/lib/usrp/e100/mboard_impl.cpp b/host/lib/usrp/e100/mboard_impl.cpp deleted file mode 100644 index e7a46fe8e..000000000 --- a/host/lib/usrp/e100/mboard_impl.cpp +++ /dev/null @@ -1,256 +0,0 @@ -// -// Copyright 2010-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 "e100_impl.hpp" -#include "e100_regs.hpp" -#include <uhd/utils/msg.hpp> -#include <uhd/exception.hpp> -#include <uhd/usrp/dsp_utils.hpp> -#include <uhd/usrp/misc_utils.hpp> -#include <uhd/usrp/mboard_props.hpp> -#include <boost/bind.hpp> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * Mboard Initialization - **********************************************************************/ -void e100_impl::mboard_init(void){ -    _mboard_proxy = wax_obj_proxy::make( -        boost::bind(&e100_impl::mboard_get, this, _1, _2), -        boost::bind(&e100_impl::mboard_set, this, _1, _2) -    ); - -    //init the clock config -    _clock_config = clock_config_t::internal(); -    update_clock_config(); -} - -void e100_impl::update_clock_config(void){ -    boost::uint32_t pps_flags = 0; - -    //translate pps polarity enums -    switch(_clock_config.pps_polarity){ -    case clock_config_t::PPS_POS: pps_flags |= E100_FLAG_TIME64_PPS_POSEDGE; break; -    case clock_config_t::PPS_NEG: pps_flags |= E100_FLAG_TIME64_PPS_NEGEDGE; break; -    default: throw uhd::value_error("unhandled clock configuration pps polarity"); -    } - -    //set the pps flags -    _iface->poke32(E100_REG_TIME64_FLAGS, pps_flags); - -    //clock source ref 10mhz -    switch(_clock_config.ref_source){ -    case clock_config_t::REF_AUTO: _clock_ctrl->use_auto_ref(); break; -    case clock_config_t::REF_INT: _clock_ctrl->use_internal_ref(); break; -    case clock_config_t::REF_SMA: _clock_ctrl->use_auto_ref(); break; -    default: throw uhd::value_error("unhandled clock configuration ref source"); -    } -} - -/*********************************************************************** - * Mboard Get - **********************************************************************/ -void e100_impl::mboard_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); -    static const std::string dboard_name = "A"; - -    //handle the get request conditioned on the key -    switch(key.as<mboard_prop_t>()){ -    case MBOARD_PROP_NAME: -        val = std::string(_iface->get_cname() + " mboard"); -        return; - -    case MBOARD_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case MBOARD_PROP_RX_DBOARD: -        UHD_ASSERT_THROW(key.name == dboard_name); -        val = _rx_dboard_proxy->get_link(); -        return; - -    case MBOARD_PROP_RX_DBOARD_NAMES: -        val = prop_names_t(1, dboard_name); -        return; - -    case MBOARD_PROP_TX_DBOARD: -        UHD_ASSERT_THROW(key.name == dboard_name); -        val = _tx_dboard_proxy->get_link(); -        return; - -    case MBOARD_PROP_TX_DBOARD_NAMES: -        val = prop_names_t(1, dboard_name); -        return; - -    case MBOARD_PROP_RX_DSP: -        val = _rx_dsp_proxies[key.name]->get_link(); -        return; - -    case MBOARD_PROP_RX_DSP_NAMES: -        val = _rx_dsp_proxies.keys(); -        return; - -    case MBOARD_PROP_TX_DSP: -        val = _tx_dsp_proxies[key.name]->get_link(); -        return; - -    case MBOARD_PROP_TX_DSP_NAMES: -        val = _tx_dsp_proxies.keys(); -        return; - -    case MBOARD_PROP_CLOCK_CONFIG: -        val = _clock_config; -        return; - -    case MBOARD_PROP_RX_SUBDEV_SPEC: -        val = _rx_subdev_spec; -        return; - -    case MBOARD_PROP_TX_SUBDEV_SPEC: -        val = _tx_subdev_spec; -        return; - -    case MBOARD_PROP_EEPROM_MAP: -        val = _iface->mb_eeprom; -        return; - -    case MBOARD_PROP_TIME_NOW: while(true){ -        uint32_t secs = _iface->peek32(E100_REG_RB_TIME_NOW_SECS); -        uint32_t ticks = _iface->peek32(E100_REG_RB_TIME_NOW_TICKS); -        if (secs != _iface->peek32(E100_REG_RB_TIME_NOW_SECS)) continue; -        val = time_spec_t(secs, ticks, _clock_ctrl->get_fpga_clock_rate()); -        return; -    } - -    case MBOARD_PROP_TIME_PPS: while(true){ -        uint32_t secs = _iface->peek32(E100_REG_RB_TIME_PPS_SECS); -        uint32_t ticks = _iface->peek32(E100_REG_RB_TIME_PPS_TICKS); -        if (secs != _iface->peek32(E100_REG_RB_TIME_PPS_SECS)) continue; -        val = time_spec_t(secs, ticks, _clock_ctrl->get_fpga_clock_rate()); -        return; -    } - -    case MBOARD_PROP_CLOCK_RATE: -        val = _clock_ctrl->get_fpga_clock_rate(); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * Mboard Set - **********************************************************************/ -void e100_impl::mboard_set(const wax::obj &key, const wax::obj &val){ -    //handle the get request conditioned on the key -    switch(key.as<mboard_prop_t>()){ - -    case MBOARD_PROP_TIME_NOW: -    case MBOARD_PROP_TIME_PPS:{ -            time_spec_t time_spec = val.as<time_spec_t>(); -            _iface->poke32(E100_REG_TIME64_TICKS, time_spec.get_tick_count(_clock_ctrl->get_fpga_clock_rate())); -            boost::uint32_t imm_flags = (key.as<mboard_prop_t>() == MBOARD_PROP_TIME_NOW)? 1 : 0; -            _iface->poke32(E100_REG_TIME64_IMM, imm_flags); -            _iface->poke32(E100_REG_TIME64_SECS, time_spec.get_full_secs()); -        } -        return; - -    case MBOARD_PROP_RX_SUBDEV_SPEC:{ -        _rx_subdev_spec = val.as<subdev_spec_t>(); -        verify_rx_subdev_spec(_rx_subdev_spec, _mboard_proxy->get_link()); -        //sanity check -        UHD_ASSERT_THROW(_rx_subdev_spec.size() <= E100_NUM_RX_DSPS); - -        //determine frontend swap IQ from the first channel -        bool fe_swap_iq = false; -        switch(_dboard_manager->get_rx_subdev(_rx_subdev_spec.at(0).sd_name)[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>()){ -        case SUBDEV_CONN_COMPLEX_QI: -        case SUBDEV_CONN_REAL_Q: -            fe_swap_iq = true; -            break; -        default: fe_swap_iq = false; -        } -        _iface->poke32(E100_REG_RX_FE_SWAP_IQ, fe_swap_iq? 1 : 0); - -        //set the dsp mux for each channel -        for (size_t i = 0; i < _rx_subdev_spec.size(); i++){ -            bool iq_swap = false, real_mode = false; -            switch(_dboard_manager->get_rx_subdev(_rx_subdev_spec.at(i).sd_name)[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>()){ -            case SUBDEV_CONN_COMPLEX_IQ: -                iq_swap = fe_swap_iq; -                real_mode = false; -                break; -            case SUBDEV_CONN_COMPLEX_QI: -                iq_swap = not fe_swap_iq; -                real_mode = false; -                break; -            case SUBDEV_CONN_REAL_I: -                iq_swap = fe_swap_iq; -                real_mode = true; -                break; -            case SUBDEV_CONN_REAL_Q: -                iq_swap = not fe_swap_iq; -                real_mode = true; -                break; -            } -            _iface->poke32(E100_REG_DSP_RX_MUX(i), -                (iq_swap?   E100_FLAG_DSP_RX_MUX_SWAP_IQ   : 0) | -                (real_mode? E100_FLAG_DSP_RX_MUX_REAL_MODE : 0) -            ); -        } -        this->update_xport_channel_mapping(); -    }return; - -    case MBOARD_PROP_TX_SUBDEV_SPEC: -        _tx_subdev_spec = val.as<subdev_spec_t>(); -        verify_tx_subdev_spec(_tx_subdev_spec, _mboard_proxy->get_link()); -        //sanity check -        UHD_ASSERT_THROW(_tx_subdev_spec.size() <= E100_NUM_TX_DSPS); -        //set the mux -        _iface->poke32(E100_REG_TX_FE_MUX, dsp_type1::calc_tx_mux_word( -            _dboard_manager->get_tx_subdev(_tx_subdev_spec.front().sd_name)[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>() -        )); -        return; - -    case MBOARD_PROP_EEPROM_MAP: -        // Step1: commit the map, writing only those values set. -        // Step2: readback the entire eeprom map into the iface. -        val.as<mboard_eeprom_t>().commit(_iface->get_i2c_dev_iface(), mboard_eeprom_t::MAP_E100); -        _iface->mb_eeprom = mboard_eeprom_t(_iface->get_i2c_dev_iface(), mboard_eeprom_t::MAP_E100); -        return; -         -    case MBOARD_PROP_CLOCK_CONFIG: -        _clock_config = val.as<clock_config_t>(); -        update_clock_config(); -        return; - -    case MBOARD_PROP_CLOCK_RATE: -        UHD_MSG(warning) -            << "I see that you are setting the master clock rate from the API.\n" -            << "You may pass this into the device address as master_clock_rate=<rate>.\n" -            << "This way, the clock rate is guaranteed to be initialized first.\n" -            << "See the application notes for USRP-E1XX for further instructions.\n" -        ; -        _clock_ctrl->set_fpga_clock_rate(val.as<double>()); -        this->update_xport_channel_mapping(); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/mboard_eeprom.cpp b/host/lib/usrp/mboard_eeprom.cpp index 2ee4a9284..79cc2f5b2 100644 --- a/host/lib/usrp/mboard_eeprom.cpp +++ b/host/lib/usrp/mboard_eeprom.cpp @@ -335,7 +335,7 @@ mboard_eeprom_t::mboard_eeprom_t(i2c_iface &iface, map_type map){      }  } -void mboard_eeprom_t::commit(i2c_iface &iface, map_type map){ +void mboard_eeprom_t::commit(i2c_iface &iface, map_type map) const{      switch(map){      case MAP_N100: store_n100(*this, iface); break;      case MAP_B000: store_b000(*this, iface); break; diff --git a/host/lib/usrp/misc_utils.cpp b/host/lib/usrp/misc_utils.cpp deleted file mode 100644 index ddcad41cf..000000000 --- a/host/lib/usrp/misc_utils.cpp +++ /dev/null @@ -1,225 +0,0 @@ -// -// Copyright 2010-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 <uhd/usrp/misc_utils.hpp> -#include <uhd/utils/assert_has.hpp> -#include <uhd/utils/algorithm.hpp> -#include <uhd/utils/gain_group.hpp> -#include <uhd/usrp/dboard_eeprom.hpp> -#include <uhd/usrp/subdev_props.hpp> -#include <uhd/usrp/mboard_props.hpp> -#include <uhd/usrp/dboard_props.hpp> -#include <uhd/usrp/codec_props.hpp> -#include <boost/bind.hpp> -#include <boost/foreach.hpp> -#include <boost/format.hpp> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * codec gain group helper functions: - *    do this so we dont have to bind a templated function - **********************************************************************/ -static gain_range_t get_codec_gain_range(wax::obj codec, const std::string &name){ -    return codec[named_prop_t(CODEC_PROP_GAIN_RANGE, name)].as<gain_range_t>(); -} - -static double get_codec_gain_i(wax::obj codec, const std::string &name){ -    return codec[named_prop_t(CODEC_PROP_GAIN_I, name)].as<double>(); -} - -static double get_codec_gain_q(wax::obj codec, const std::string &name){ -    return codec[named_prop_t(CODEC_PROP_GAIN_Q, name)].as<double>(); -} - -static void set_codec_gain_both(wax::obj codec, const std::string &name, double gain){ -    codec[named_prop_t(CODEC_PROP_GAIN_I, name)] = gain; -    codec[named_prop_t(CODEC_PROP_GAIN_Q, name)] = gain; -} - -static void set_codec_gain_i(wax::obj codec, const std::string &name, double gain){ -    codec[named_prop_t(CODEC_PROP_GAIN_I, name)] = gain; -} - -static void set_codec_gain_q(wax::obj codec, const std::string &name, double gain){ -    codec[named_prop_t(CODEC_PROP_GAIN_Q, name)] = gain; -} - -/*********************************************************************** - * subdev gain group helper functions: - *    do this so we dont have to bind a templated function - **********************************************************************/ -static double get_subdev_gain(wax::obj subdev, const std::string &name){ -    return subdev[named_prop_t(SUBDEV_PROP_GAIN, name)].as<double>(); -} - -static gain_range_t get_subdev_gain_range(wax::obj subdev, const std::string &name){ -    return subdev[named_prop_t(SUBDEV_PROP_GAIN_RANGE, name)].as<gain_range_t>(); -} - -static void set_subdev_gain(wax::obj subdev, const std::string &name, double gain){ -    subdev[named_prop_t(SUBDEV_PROP_GAIN, name)] = gain; -} - -/*********************************************************************** - * gain group factory function for usrp - **********************************************************************/ -gain_group::sptr usrp::make_gain_group( -    const dboard_id_t &dboard_id, -    wax::obj subdev, wax::obj codec, -    gain_group_policy_t gain_group_policy -){ -    const size_t subdev_gain_priority = 1; -    const size_t codec_gain_priority = (gain_group_policy == GAIN_GROUP_POLICY_RX)? -        (subdev_gain_priority - 1): //RX policy, codec gains fill last (lower priority) -        (subdev_gain_priority + 1); //TX policy, codec gains fill first (higher priority) -    const std::string subdev_prefix = dboard_id.to_cname() + "-"; -    const std::string codec_prefix = (gain_group_policy == GAIN_GROUP_POLICY_RX)? "ADC-" : "DAC-"; - -    gain_group::sptr gg = gain_group::make(); -    gain_fcns_t fcns; -    //add all the subdev gains first (antenna to dsp order) -    BOOST_FOREACH(const std::string &name, subdev[SUBDEV_PROP_GAIN_NAMES].as<prop_names_t>()){ -        fcns.get_range = boost::bind(&get_subdev_gain_range, subdev, name); -        fcns.get_value = boost::bind(&get_subdev_gain, subdev, name); -        fcns.set_value = boost::bind(&set_subdev_gain, subdev, name, _1); -        gg->register_fcns(subdev_prefix+name, fcns, subdev_gain_priority); -    } -    //add all the codec gains last (antenna to dsp order) -    BOOST_FOREACH(const std::string &name, codec[CODEC_PROP_GAIN_NAMES].as<prop_names_t>()){ -        fcns.get_range = boost::bind(&get_codec_gain_range, codec, name); - -        //register the value functions depending upon the connection type -        switch(subdev[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>()){ -        case SUBDEV_CONN_COMPLEX_IQ: -        case SUBDEV_CONN_COMPLEX_QI: -            fcns.get_value = boost::bind(&get_codec_gain_i, codec, name); //same as Q -            fcns.set_value = boost::bind(&set_codec_gain_both, codec, name, _1); //sets both -            break; - -        case SUBDEV_CONN_REAL_I: -            fcns.get_value = boost::bind(&get_codec_gain_i, codec, name); -            fcns.set_value = boost::bind(&set_codec_gain_i, codec, name, _1); -            break; - -        case SUBDEV_CONN_REAL_Q: -            fcns.get_value = boost::bind(&get_codec_gain_q, codec, name); -            fcns.set_value = boost::bind(&set_codec_gain_q, codec, name, _1); -            break; -        } -        gg->register_fcns(codec_prefix+name, fcns, codec_gain_priority); -    } -    return gg; -} - -/*********************************************************************** - * verify subdev specs - **********************************************************************/ -static void verify_xx_subdev_spec( -    mboard_prop_t dboard_names_prop, -    mboard_prop_t dboard_prop, -    subdev_spec_t &subdev_spec, -    wax::obj mboard, -    std::string xx_type -){ -    try{ -        prop_names_t dboard_names = mboard[dboard_names_prop].as<prop_names_t>(); -        UHD_ASSERT_THROW(dboard_names.size() > 0); //well i hope there is a dboard - -        //the subdevice specification is empty: handle automatic -        if (subdev_spec.empty()){ -            BOOST_FOREACH(const std::string &db_name, dboard_names){ -                wax::obj dboard = mboard[named_prop_t(dboard_prop, db_name)]; - -                //if the dboard slot is populated, take the first subdevice -                if (dboard[DBOARD_PROP_DBOARD_EEPROM].as<dboard_eeprom_t>().id != dboard_id_t::none()){ -                    std::string sd_name = dboard[DBOARD_PROP_SUBDEV_NAMES].as<prop_names_t>().front(); -                    subdev_spec.push_back(subdev_spec_pair_t(db_name, sd_name)); -                    break; -                } -            } - -            //didnt find any populated dboards: add the first subdevice -            if (subdev_spec.empty()){ -                std::string db_name = dboard_names.front(); -                wax::obj dboard = mboard[named_prop_t(dboard_prop, db_name)]; -                std::string sd_name = dboard[DBOARD_PROP_SUBDEV_NAMES].as<prop_names_t>().front(); -                subdev_spec.push_back(subdev_spec_pair_t(db_name, sd_name)); -            } -        } - -        //sanity check that the dboard/subdevice names exist for this mboard -        BOOST_FOREACH(subdev_spec_pair_t &pair, subdev_spec){ -            //empty db name means select dboard automatically -            if (pair.db_name.empty()){ -                if (dboard_names.size() != 1) throw uhd::value_error( -                    "A daughterboard name must be provided for multi-slot motherboards: " + subdev_spec.to_string() -                ); -                pair.db_name = dboard_names.front(); -            } -            uhd::assert_has(dboard_names, pair.db_name, xx_type + " dboard name"); -            wax::obj dboard = mboard[named_prop_t(dboard_prop, pair.db_name)]; -            prop_names_t subdev_names = dboard[DBOARD_PROP_SUBDEV_NAMES].as<prop_names_t>(); - -            //empty sd name means select the subdev automatically -            if (pair.sd_name.empty()){ -                if (subdev_names.size() != 1) throw uhd::value_error( -                    "A subdevice name must be provided for multi-subdev daughterboards: " + subdev_spec.to_string() -                ); -                pair.sd_name = subdev_names.front(); -            } -            uhd::assert_has(subdev_names, pair.sd_name, xx_type + " subdev name"); -        } -    }catch(const std::exception &e){ -        throw uhd::value_error(str(boost::format( -            "Validate %s subdev spec failed: %s\n    %s" -        ) % xx_type % subdev_spec.to_string() % e.what())); -    } - -    //now use the subdev spec to enable the subdevices in use and vice-versa -    BOOST_FOREACH(const std::string &db_name, mboard[dboard_names_prop].as<prop_names_t>()){ -        wax::obj dboard = mboard[named_prop_t(dboard_prop, db_name)]; -        BOOST_FOREACH(const std::string &sd_name, dboard[DBOARD_PROP_SUBDEV_NAMES].as<prop_names_t>()){ -            try{ -                bool enable = uhd::has(subdev_spec, subdev_spec_pair_t(db_name, sd_name)); -                dboard[named_prop_t(DBOARD_PROP_SUBDEV, sd_name)][SUBDEV_PROP_ENABLED] = enable; -            } -            catch(const std::exception &e){ -                throw uhd::runtime_error(str(boost::format( -                    "Cannot set enabled property on subdevice %s:%s\n    %s" -                ) % db_name % sd_name % e.what())); -            } -        } -    } -} - -void usrp::verify_rx_subdev_spec(subdev_spec_t &subdev_spec, wax::obj mboard){ -    return verify_xx_subdev_spec( -        MBOARD_PROP_RX_DBOARD_NAMES, -        MBOARD_PROP_RX_DBOARD, -        subdev_spec, mboard, "rx" -    ); -} - -void usrp::verify_tx_subdev_spec(subdev_spec_t &subdev_spec, wax::obj mboard){ -    return verify_xx_subdev_spec( -        MBOARD_PROP_TX_DBOARD_NAMES, -        MBOARD_PROP_TX_DBOARD, -        subdev_spec, mboard, "tx" -    ); -} diff --git a/host/lib/usrp/multi_usrp.cpp b/host/lib/usrp/multi_usrp.cpp index 64f82e559..2f416d93a 100644 --- a/host/lib/usrp/multi_usrp.cpp +++ b/host/lib/usrp/multi_usrp.cpp @@ -15,18 +15,13 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // +#include <uhd/property_tree.hpp>  #include <uhd/usrp/multi_usrp.hpp> -#include <uhd/usrp/tune_helper.hpp>  #include <uhd/usrp/mboard_iface.hpp>  #include <uhd/utils/msg.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/msg.hpp>  #include <uhd/utils/gain_group.hpp> -#include <uhd/usrp/subdev_props.hpp> -#include <uhd/usrp/mboard_props.hpp> -#include <uhd/usrp/device_props.hpp> -#include <uhd/usrp/dboard_props.hpp> -#include <uhd/usrp/dsp_props.hpp>  #include <boost/thread.hpp>  #include <boost/foreach.hpp>  #include <boost/format.hpp> @@ -40,15 +35,7 @@ const std::string multi_usrp::ALL_GAINS = "";  /***********************************************************************   * Helper methods   **********************************************************************/ -static inline uhd::freq_range_t add_dsp_shift( -    const uhd::freq_range_t &range, -    wax::obj dsp -){ -    double codec_rate = dsp[uhd::usrp::DSP_PROP_CODEC_RATE].as<double>(); -    return uhd::freq_range_t(range.start() - codec_rate/2.0, range.stop() + codec_rate/2.0); -} - -static inline void do_samp_rate_warning_message( +static void do_samp_rate_warning_message(      double target_rate,      double actual_rate,      const std::string &xx @@ -63,7 +50,7 @@ static inline void do_samp_rate_warning_message(      }  } -static inline void do_tune_freq_warning_message( +static void do_tune_freq_warning_message(      double target_freq,      double actual_freq,      const std::string &xx @@ -79,12 +66,130 @@ static inline void do_tune_freq_warning_message(  }  /*********************************************************************** + * Gain helper functions + **********************************************************************/ +static double get_gain_value(property_tree::sptr tree, const property_tree::path_type &path){ +    return tree->access<double>(path / "value").get(); +} + +static void set_gain_value(property_tree::sptr tree, const property_tree::path_type &path, const double gain){ +    tree->access<double>(path / "value").set(gain); +} + +static meta_range_t get_gain_range(property_tree::sptr tree, const property_tree::path_type &path){ +    return tree->access<meta_range_t>(path / "range").get(); +} + +static gain_fcns_t make_gain_fcns_from_path(property_tree::sptr tree, const property_tree::path_type &path){ +    gain_fcns_t gain_fcns; +    gain_fcns.get_range = boost::bind(&get_gain_range, tree, path); +    gain_fcns.get_value = boost::bind(&get_gain_value, tree, path); +    gain_fcns.set_value = boost::bind(&set_gain_value, tree, path, _1); +    return gain_fcns; +} + +/*********************************************************************** + * Tune Helper Functions + **********************************************************************/ +static const double RX_SIGN = +1.0; +static const double TX_SIGN = -1.0; + +static tune_result_t tune_xx_subdev_and_dsp( +    const double xx_sign, +    property_tree::sptr tree, +    const property_tree::path_type &dsp_path, +    const property_tree::path_type &rf_fe_path, +    const tune_request_t &tune_request +){ +    //------------------------------------------------------------------ +    //-- calculate the LO offset, only used with automatic policy +    //------------------------------------------------------------------ +    double lo_offset = 0.0; +    if (tree->access<bool>(rf_fe_path / "use_lo_offset").get()){ +        //If the local oscillator will be in the passband, use an offset. +        //But constrain the LO offset by the width of the filter bandwidth. +        const double rate = tree->access<double>(dsp_path / "rate" / "value").get(); +        const double bw = tree->access<double>(rf_fe_path / "bandwidth" / "value").get(); +        if (bw > rate) lo_offset = std::min((bw - rate)/2, rate/2); +    } + +    //------------------------------------------------------------------ +    //-- set the RF frequency depending upon the policy +    //------------------------------------------------------------------ +    double target_rf_freq = 0.0; +    switch (tune_request.rf_freq_policy){ +    case tune_request_t::POLICY_AUTO: +        target_rf_freq = tune_request.target_freq + lo_offset; +        tree->access<double>(rf_fe_path / "freq" / "value").set(target_rf_freq); +        break; + +    case tune_request_t::POLICY_MANUAL: +        target_rf_freq = tune_request.rf_freq; +        tree->access<double>(rf_fe_path / "freq" / "value").set(target_rf_freq); +        break; + +    case tune_request_t::POLICY_NONE: break; //does not set +    } +    const double actual_rf_freq = tree->access<double>(rf_fe_path / "freq" / "value").get(); + +    //------------------------------------------------------------------ +    //-- calculate the dsp freq, only used with automatic policy +    //------------------------------------------------------------------ +    double target_dsp_freq = actual_rf_freq - tune_request.target_freq; + +    //invert the sign on the dsp freq for transmit +    target_dsp_freq *= xx_sign; + +    //------------------------------------------------------------------ +    //-- set the dsp frequency depending upon the dsp frequency policy +    //------------------------------------------------------------------ +    switch (tune_request.dsp_freq_policy){ +    case tune_request_t::POLICY_AUTO: +        tree->access<double>(dsp_path / "freq" / "value").set(target_dsp_freq); +        break; + +    case tune_request_t::POLICY_MANUAL: +        target_dsp_freq = tune_request.dsp_freq; +        tree->access<double>(dsp_path / "freq" / "value").set(target_dsp_freq); +        break; + +    case tune_request_t::POLICY_NONE: break; //does not set +    } +    const double actual_dsp_freq = tree->access<double>(dsp_path / "freq" / "value").get(); + +    //------------------------------------------------------------------ +    //-- load and return the tune result +    //------------------------------------------------------------------ +    tune_result_t tune_result; +    tune_result.target_rf_freq = target_rf_freq; +    tune_result.actual_rf_freq = actual_rf_freq; +    tune_result.target_dsp_freq = target_dsp_freq; +    tune_result.actual_dsp_freq = actual_dsp_freq; +    return tune_result; +} + +static double derive_freq_from_xx_subdev_and_dsp( +    const double xx_sign, +    property_tree::sptr tree, +    const property_tree::path_type &dsp_path, +    const property_tree::path_type &rf_fe_path +){ +    //extract actual dsp and IF frequencies +    const double actual_rf_freq = tree->access<double>(rf_fe_path / "freq" / "value").get(); +    const double actual_dsp_freq = tree->access<double>(dsp_path / "freq" / "value").get(); + +    //invert the sign on the dsp freq for transmit +    return actual_rf_freq - actual_dsp_freq * xx_sign; +} + +/***********************************************************************   * Multi USRP Implementation   **********************************************************************/  class multi_usrp_impl : public multi_usrp{  public:      multi_usrp_impl(const device_addr_t &addr){          _dev = device::make(addr); +        _tree = (*_dev)[0].as<property_tree::sptr>();      }      device::sptr get_device(void){ @@ -96,7 +201,7 @@ public:       ******************************************************************/      void set_master_clock_rate(double rate, size_t mboard){          if (mboard != ALL_MBOARDS){ -            _mboard(mboard)[MBOARD_PROP_CLOCK_RATE] = rate; +            _tree->access<double>(mb_root(mboard) / "tick_rate").set(rate);              return;          }          for (size_t m = 0; m < get_num_mboards(); m++){ @@ -105,7 +210,7 @@ public:      }      double get_master_clock_rate(size_t mboard){ -        return _mboard(mboard)[MBOARD_PROP_CLOCK_RATE].as<double>(); +        return _tree->access<double>(mb_root(mboard) / "tick_rate").get();      }      std::string get_pp_string(void){ @@ -114,13 +219,13 @@ public:              "  Device: %s\n"          )              % ((get_num_mboards() > 1)? "Multi" : "Single") -            % (*_dev)[DEVICE_PROP_NAME].as<std::string>() +            % (_tree->access<std::string>("/name").get())          );          for (size_t m = 0; m < get_num_mboards(); m++){              buff += str(boost::format(                  "  Mboard %d: %s\n"              ) % m -                % _mboard(m)[MBOARD_PROP_NAME].as<std::string>() +                % (_tree->access<std::string>(mb_root(m) / "name").get())              );          } @@ -133,9 +238,9 @@ public:                      "    RX Dboard: %s\n"                      "    RX Subdev: %s\n"                  ) % chan -                    % _rx_dsp(chan)[DSP_PROP_NAME].as<std::string>() -                    % _rx_dboard(chan)[DBOARD_PROP_NAME].as<std::string>() -                    % _rx_subdev(chan)[SUBDEV_PROP_NAME].as<std::string>() +                    % rx_dsp_root(chan).leaf() +                    % rx_rf_fe_root(chan).branch_path().branch_path().leaf() +                    % (_tree->access<std::string>(rx_rf_fe_root(chan) / "name").get())                  );              }          } @@ -149,9 +254,9 @@ public:                      "    TX Dboard: %s\n"                      "    TX Subdev: %s\n"                  ) % chan -                    % _tx_dsp(chan)[DSP_PROP_NAME].as<std::string>() -                    % _tx_dboard(chan)[DBOARD_PROP_NAME].as<std::string>() -                    % _tx_subdev(chan)[SUBDEV_PROP_NAME].as<std::string>() +                    % tx_dsp_root(chan).leaf() +                    % tx_rf_fe_root(chan).branch_path().branch_path().leaf() +                    % (_tree->access<std::string>(tx_rf_fe_root(chan) / "name").get())                  );              }          } @@ -160,20 +265,20 @@ public:      }      std::string get_mboard_name(size_t mboard){ -        return _mboard(mboard)[MBOARD_PROP_NAME].as<std::string>(); +        return _tree->access<std::string>(mb_root(mboard) / "name").get();      }      time_spec_t get_time_now(size_t mboard = 0){ -        return _mboard(mboard)[MBOARD_PROP_TIME_NOW].as<time_spec_t>(); +        return _tree->access<time_spec_t>(mb_root(mboard) / "time/now").get();      }      time_spec_t get_time_last_pps(size_t mboard = 0){ -        return _mboard(mboard)[MBOARD_PROP_TIME_PPS].as<time_spec_t>(); +        return _tree->access<time_spec_t>(mb_root(mboard) / "time/pps").get();      }      void set_time_now(const time_spec_t &time_spec, size_t mboard){          if (mboard != ALL_MBOARDS){ -            _mboard(mboard)[MBOARD_PROP_TIME_NOW] = time_spec; +            _tree->access<time_spec_t>(mb_root(mboard) / "time/now").set(time_spec);              return;          }          for (size_t m = 0; m < get_num_mboards(); m++){ @@ -183,7 +288,7 @@ public:      void set_time_next_pps(const time_spec_t &time_spec){          for (size_t m = 0; m < get_num_mboards(); m++){ -            _mboard(m)[MBOARD_PROP_TIME_PPS] = time_spec; +            _tree->access<time_spec_t>(mb_root(m) / "time/pps").set(time_spec);          }      } @@ -208,8 +313,8 @@ public:          //verify that the time registers are read to be within a few RTT          for (size_t m = 1; m < get_num_mboards(); m++){ -            time_spec_t time_0 = _mboard(0)[MBOARD_PROP_TIME_NOW].as<time_spec_t>(); -            time_spec_t time_i = _mboard(m)[MBOARD_PROP_TIME_NOW].as<time_spec_t>(); +            time_spec_t time_0 = this->get_time_now(0); +            time_spec_t time_i = this->get_time_now(m);              if (time_i < time_0 or (time_i - time_0) > time_spec_t(0.01)){ //10 ms: greater than RTT but not too big                  UHD_MSG(warning) << boost::format(                      "Detected time deviation between board %d and board 0.\n" @@ -222,8 +327,8 @@ public:      bool get_time_synchronized(void){          for (size_t m = 1; m < get_num_mboards(); m++){ -            time_spec_t time_0 = _mboard(0)[MBOARD_PROP_TIME_NOW].as<time_spec_t>(); -            time_spec_t time_i = _mboard(m)[MBOARD_PROP_TIME_NOW].as<time_spec_t>(); +            time_spec_t time_0 = this->get_time_now(0); +            time_spec_t time_i = this->get_time_now(m);              if (time_i < time_0 or (time_i - time_0) > time_spec_t(0.01)) return false;          }          return true; @@ -231,7 +336,7 @@ public:      void issue_stream_cmd(const stream_cmd_t &stream_cmd, size_t chan){          if (chan != ALL_CHANS){ -            _rx_dsp(chan)[DSP_PROP_STREAM_CMD] = stream_cmd; +            _tree->access<stream_cmd_t>(rx_dsp_root(chan) / "stream_cmd").set(stream_cmd);              return;          }          for (size_t c = 0; c < get_rx_num_channels(); c++){ @@ -241,7 +346,26 @@ public:      void set_clock_config(const clock_config_t &clock_config, size_t mboard){          if (mboard != ALL_MBOARDS){ -            _mboard(mboard)[MBOARD_PROP_CLOCK_CONFIG] = clock_config; +            //set the reference source... +            std::string clock_source; +            switch(clock_config.ref_source){ +            case clock_config_t::REF_INT: clock_source = "internal"; break; +            case clock_config_t::PPS_SMA: clock_source = "external"; break; +            case clock_config_t::PPS_MIMO: clock_source = "mimo"; break; +            default: clock_source = "unknown"; +            } +            if (clock_source == "external" and clock_config.pps_polarity == clock_config_t::PPS_NEG) clock_source = "_external_"; +            _tree->access<std::string>(mb_root(mboard) / "clock_source" / "value").set(clock_source); + +            //set the time source +            std::string time_source; +            switch(clock_config.pps_source){ +            case clock_config_t::PPS_INT: time_source = "internal"; break; +            case clock_config_t::PPS_SMA: time_source = "external"; break; +            case clock_config_t::PPS_MIMO: time_source = "mimo"; break; +            default: time_source = "unknown"; +            } +            _tree->access<std::string>(mb_root(mboard) / "time_source" / "value").set(time_source);              return;          }          for (size_t m = 0; m < get_num_mboards(); m++){ @@ -250,19 +374,19 @@ public:      }      size_t get_num_mboards(void){ -        return (*_dev)[DEVICE_PROP_MBOARD_NAMES].as<prop_names_t>().size(); +        return _tree->list("/mboards").size();      }      sensor_value_t get_mboard_sensor(const std::string &name, size_t mboard){ -        return _mboard(mboard)[named_prop_t(MBOARD_PROP_SENSOR, name)].as<sensor_value_t>(); +        return _tree->access<sensor_value_t>(mb_root(mboard) / "sensors" / name).get();      }      std::vector<std::string> get_mboard_sensor_names(size_t mboard){ -        return _mboard(mboard)[MBOARD_PROP_SENSOR_NAMES].as<prop_names_t>(); +        return _tree->list(mb_root(mboard) / "sensors");      } -     -    mboard_iface::sptr get_mboard_iface(size_t mboard){ -        return _mboard(mboard)[MBOARD_PROP_IFACE].as<mboard_iface::sptr>(); + +    mboard_iface::sptr get_mboard_iface(size_t){ +        return mboard_iface::sptr(); //not implemented      }      /******************************************************************* @@ -270,7 +394,7 @@ public:       ******************************************************************/      void set_rx_subdev_spec(const subdev_spec_t &spec, size_t mboard){          if (mboard != ALL_MBOARDS){ -            _mboard(mboard)[MBOARD_PROP_RX_SUBDEV_SPEC] = spec; +            _tree->access<subdev_spec_t>(mb_root(mboard) / "rx_subdev_spec").set(spec);              return;          }          for (size_t m = 0; m < get_num_mboards(); m++){ @@ -279,7 +403,7 @@ public:      }      subdev_spec_t get_rx_subdev_spec(size_t mboard){ -        return _mboard(mboard)[MBOARD_PROP_RX_SUBDEV_SPEC].as<subdev_spec_t>(); +        return _tree->access<subdev_spec_t>(mb_root(mboard) / "rx_subdev_spec").get();      }      size_t get_rx_num_channels(void){ @@ -291,12 +415,12 @@ public:      }      std::string get_rx_subdev_name(size_t chan){ -        return _rx_subdev(chan)[SUBDEV_PROP_NAME].as<std::string>(); +        return _tree->access<std::string>(rx_rf_fe_root(chan) / "name").get();      }      void set_rx_rate(double rate, size_t chan){          if (chan != ALL_CHANS){ -            _rx_dsp(chan)[DSP_PROP_HOST_RATE] = rate; +            _tree->access<double>(rx_dsp_root(chan) / "rate" / "value").set(rate);              do_samp_rate_warning_message(rate, get_rx_rate(chan), "RX");              return;          } @@ -306,69 +430,71 @@ public:      }      double get_rx_rate(size_t chan){ -        return _rx_dsp(chan)[DSP_PROP_HOST_RATE].as<double>(); +        return _tree->access<double>(rx_dsp_root(chan) / "rate" / "value").get();      }      tune_result_t set_rx_freq(const tune_request_t &tune_request, size_t chan){ -        tune_result_t r = tune_rx_subdev_and_dsp(_rx_subdev(chan), _rx_dsp(chan), tune_request); +        tune_result_t r = tune_xx_subdev_and_dsp(RX_SIGN, _tree, rx_dsp_root(chan), rx_rf_fe_root(chan), tune_request);          do_tune_freq_warning_message(tune_request.target_freq, get_rx_freq(chan), "RX");          return r;      }      double get_rx_freq(size_t chan){ -        return derive_freq_from_rx_subdev_and_dsp(_rx_subdev(chan), _rx_dsp(chan)); +        return derive_freq_from_xx_subdev_and_dsp(RX_SIGN, _tree, rx_dsp_root(chan), rx_rf_fe_root(chan));      }      freq_range_t get_rx_freq_range(size_t chan){ -        return add_dsp_shift(_rx_subdev(chan)[SUBDEV_PROP_FREQ_RANGE].as<freq_range_t>(), _rx_dsp(chan)); +        meta_range_t range = _tree->access<meta_range_t>(rx_rf_fe_root(chan) / "freq" / "range").get(); +        meta_range_t dsp_range = _tree->access<meta_range_t>(rx_dsp_root(chan) / "freq" / "range").get(); +        return meta_range_t(range.start() + dsp_range.start(), range.stop() + dsp_range.stop(), dsp_range.step());      }      void set_rx_gain(double gain, const std::string &name, size_t chan){ -        return _rx_gain_group(chan)->set_value(gain, name); +        return rx_gain_group(chan)->set_value(gain, name);      }      double get_rx_gain(const std::string &name, size_t chan){ -        return _rx_gain_group(chan)->get_value(name); +        return rx_gain_group(chan)->get_value(name);      }      gain_range_t get_rx_gain_range(const std::string &name, size_t chan){ -        return _rx_gain_group(chan)->get_range(name); +        return rx_gain_group(chan)->get_range(name);      }      std::vector<std::string> get_rx_gain_names(size_t chan){ -        return _rx_gain_group(chan)->get_names(); +        return rx_gain_group(chan)->get_names();      }      void set_rx_antenna(const std::string &ant, size_t chan){ -        _rx_subdev(chan)[SUBDEV_PROP_ANTENNA] = ant; +        _tree->access<std::string>(rx_rf_fe_root(chan) / "antenna" / "value").set(ant);      }      std::string get_rx_antenna(size_t chan){ -        return _rx_subdev(chan)[SUBDEV_PROP_ANTENNA].as<std::string>(); +        return _tree->access<std::string>(rx_rf_fe_root(chan) / "antenna" / "value").get();      }      std::vector<std::string> get_rx_antennas(size_t chan){ -        return _rx_subdev(chan)[SUBDEV_PROP_ANTENNA_NAMES].as<prop_names_t>(); +        return _tree->access<std::vector<std::string> >(rx_rf_fe_root(chan) / "antenna" / "options").get();      }      void set_rx_bandwidth(double bandwidth, size_t chan){ -        _rx_subdev(chan)[SUBDEV_PROP_BANDWIDTH] = bandwidth; +        _tree->access<double>(rx_rf_fe_root(chan) / "bandwidth" / "value").set(bandwidth);      }      double get_rx_bandwidth(size_t chan){ -        return _rx_subdev(chan)[SUBDEV_PROP_BANDWIDTH].as<double>(); +        return _tree->access<double>(rx_rf_fe_root(chan) / "bandwidth" / "value").get();      }      dboard_iface::sptr get_rx_dboard_iface(size_t chan){ -        return _rx_dboard(chan)[DBOARD_PROP_DBOARD_IFACE].as<dboard_iface::sptr>(); +        return _tree->access<dboard_iface::sptr>(rx_rf_fe_root(chan).branch_path().branch_path() / "iface").get();      }      sensor_value_t get_rx_sensor(const std::string &name, size_t chan){ -        return _rx_subdev(chan)[named_prop_t(SUBDEV_PROP_SENSOR, name)].as<sensor_value_t>(); +        return _tree->access<sensor_value_t>(rx_rf_fe_root(chan) / "sensors" / name).get();      }      std::vector<std::string> get_rx_sensor_names(size_t chan){ -        return _rx_subdev(chan)[SUBDEV_PROP_SENSOR_NAMES].as<prop_names_t>(); +        return _tree->list(rx_rf_fe_root(chan) / "sensors");      }      /******************************************************************* @@ -376,7 +502,7 @@ public:       ******************************************************************/      void set_tx_subdev_spec(const subdev_spec_t &spec, size_t mboard){          if (mboard != ALL_MBOARDS){ -            _mboard(mboard)[MBOARD_PROP_TX_SUBDEV_SPEC] = spec; +            _tree->access<subdev_spec_t>(mb_root(mboard) / "tx_subdev_spec").set(spec);              return;          }          for (size_t m = 0; m < get_num_mboards(); m++){ @@ -385,11 +511,11 @@ public:      }      subdev_spec_t get_tx_subdev_spec(size_t mboard){ -        return _mboard(mboard)[MBOARD_PROP_TX_SUBDEV_SPEC].as<subdev_spec_t>(); +        return _tree->access<subdev_spec_t>(mb_root(mboard) / "tx_subdev_spec").get();      }      std::string get_tx_subdev_name(size_t chan){ -        return _tx_subdev(chan)[SUBDEV_PROP_NAME].as<std::string>(); +        return _tree->access<std::string>(tx_rf_fe_root(chan) / "name").get();      }      size_t get_tx_num_channels(void){ @@ -402,7 +528,7 @@ public:      void set_tx_rate(double rate, size_t chan){          if (chan != ALL_CHANS){ -            _tx_dsp(chan)[DSP_PROP_HOST_RATE] = rate; +            _tree->access<double>(tx_dsp_root(chan) / "rate" / "value").set(rate);              do_samp_rate_warning_message(rate, get_tx_rate(chan), "TX");              return;          } @@ -412,73 +538,76 @@ public:      }      double get_tx_rate(size_t chan){ -        return _tx_dsp(chan)[DSP_PROP_HOST_RATE].as<double>(); +        return _tree->access<double>(tx_dsp_root(chan) / "rate" / "value").get();      }      tune_result_t set_tx_freq(const tune_request_t &tune_request, size_t chan){ -        tune_result_t r = tune_tx_subdev_and_dsp(_tx_subdev(chan), _tx_dsp(chan), tune_request); +        tune_result_t r = tune_xx_subdev_and_dsp(TX_SIGN, _tree, tx_dsp_root(chan), tx_rf_fe_root(chan), tune_request);          do_tune_freq_warning_message(tune_request.target_freq, get_tx_freq(chan), "TX");          return r;      }      double get_tx_freq(size_t chan){ -        return derive_freq_from_tx_subdev_and_dsp(_tx_subdev(chan), _tx_dsp(chan)); +        return derive_freq_from_xx_subdev_and_dsp(TX_SIGN, _tree, tx_dsp_root(chan), tx_rf_fe_root(chan));      }      freq_range_t get_tx_freq_range(size_t chan){ -        return add_dsp_shift(_tx_subdev(chan)[SUBDEV_PROP_FREQ_RANGE].as<freq_range_t>(), _tx_dsp(chan)); +        meta_range_t range = _tree->access<meta_range_t>(tx_rf_fe_root(chan) / "freq" / "range").get(); +        meta_range_t dsp_range = _tree->access<meta_range_t>(tx_dsp_root(chan) / "freq" / "range").get(); +        return meta_range_t(range.start() + dsp_range.start(), range.stop() + dsp_range.stop(), dsp_range.step());      }      void set_tx_gain(double gain, const std::string &name, size_t chan){ -        return _tx_gain_group(chan)->set_value(gain, name); +        return tx_gain_group(chan)->set_value(gain, name);      }      double get_tx_gain(const std::string &name, size_t chan){ -        return _tx_gain_group(chan)->get_value(name); +        return tx_gain_group(chan)->get_value(name);      }      gain_range_t get_tx_gain_range(const std::string &name, size_t chan){ -        return _tx_gain_group(chan)->get_range(name); +        return tx_gain_group(chan)->get_range(name);      }      std::vector<std::string> get_tx_gain_names(size_t chan){ -        return _tx_gain_group(chan)->get_names(); +        return tx_gain_group(chan)->get_names();      }      void set_tx_antenna(const std::string &ant, size_t chan){ -        _tx_subdev(chan)[SUBDEV_PROP_ANTENNA] = ant; +        _tree->access<std::string>(tx_rf_fe_root(chan) / "antenna" / "value").set(ant);      }      std::string get_tx_antenna(size_t chan){ -        return _tx_subdev(chan)[SUBDEV_PROP_ANTENNA].as<std::string>(); +        return _tree->access<std::string>(tx_rf_fe_root(chan) / "antenna" / "value").get();      }      std::vector<std::string> get_tx_antennas(size_t chan){ -        return _tx_subdev(chan)[SUBDEV_PROP_ANTENNA_NAMES].as<prop_names_t>(); +        return _tree->access<std::vector<std::string> >(tx_rf_fe_root(chan) / "antenna" / "options").get();      }      void set_tx_bandwidth(double bandwidth, size_t chan){ -        _tx_subdev(chan)[SUBDEV_PROP_BANDWIDTH] = bandwidth; +        _tree->access<double>(tx_rf_fe_root(chan) / "bandwidth" / "value").set(bandwidth);      }      double get_tx_bandwidth(size_t chan){ -        return _tx_subdev(chan)[SUBDEV_PROP_BANDWIDTH].as<double>(); +        return _tree->access<double>(tx_rf_fe_root(chan) / "bandwidth" / "value").get();      }      dboard_iface::sptr get_tx_dboard_iface(size_t chan){ -        return _tx_dboard(chan)[DBOARD_PROP_DBOARD_IFACE].as<dboard_iface::sptr>(); +        return _tree->access<dboard_iface::sptr>(tx_rf_fe_root(chan).branch_path().branch_path() / "iface").get();      }      sensor_value_t get_tx_sensor(const std::string &name, size_t chan){ -        return _tx_subdev(chan)[named_prop_t(SUBDEV_PROP_SENSOR, name)].as<sensor_value_t>(); +        return _tree->access<sensor_value_t>(tx_rf_fe_root(chan) / "sensors" / name).get();      }      std::vector<std::string> get_tx_sensor_names(size_t chan){ -        return _tx_subdev(chan)[SUBDEV_PROP_SENSOR_NAMES].as<prop_names_t>(); +        return _tree->list(tx_rf_fe_root(chan) / "sensors");      }  private:      device::sptr _dev; +    property_tree::sptr _tree;      struct mboard_chan_pair{          size_t mboard, chan; @@ -507,49 +636,59 @@ private:          return mcp;      } -    wax::obj _mboard(size_t mboard){ -        std::string mb_name = (*_dev)[DEVICE_PROP_MBOARD_NAMES].as<prop_names_t>().at(mboard); -        return (*_dev)[named_prop_t(DEVICE_PROP_MBOARD, mb_name)]; +    property_tree::path_type mb_root(const size_t mboard){ +        const std::string name = _tree->list("/mboards").at(mboard); +        return "/mboards/" + name;      } -    wax::obj _rx_dsp(size_t chan){ -        mboard_chan_pair mcp = rx_chan_to_mcp(chan); -        prop_names_t dsp_names = _mboard(mcp.mboard)[MBOARD_PROP_RX_DSP_NAMES].as<prop_names_t>(); -        return _mboard(mcp.mboard)[named_prop_t(MBOARD_PROP_RX_DSP, dsp_names.at(mcp.chan))]; -    } -    wax::obj _tx_dsp(size_t chan){ -        mboard_chan_pair mcp = tx_chan_to_mcp(chan); -        prop_names_t dsp_names = _mboard(mcp.mboard)[MBOARD_PROP_TX_DSP_NAMES].as<prop_names_t>(); -        return _mboard(mcp.mboard)[named_prop_t(MBOARD_PROP_TX_DSP, dsp_names.at(mcp.chan))]; -    } -    wax::obj _rx_dboard(size_t chan){ + +    property_tree::path_type rx_dsp_root(const size_t chan){          mboard_chan_pair mcp = rx_chan_to_mcp(chan); -        std::string db_name = get_rx_subdev_spec(mcp.mboard).at(mcp.chan).db_name; -        return _mboard(mcp.mboard)[named_prop_t(MBOARD_PROP_RX_DBOARD, db_name)]; +        const std::string name = _tree->list(mb_root(mcp.mboard) / "rx_dsps").at(mcp.chan); +        return mb_root(mcp.mboard) / "rx_dsps" / name;      } -    wax::obj _tx_dboard(size_t chan){ + +    property_tree::path_type tx_dsp_root(const size_t chan){          mboard_chan_pair mcp = tx_chan_to_mcp(chan); -        std::string db_name = get_tx_subdev_spec(mcp.mboard).at(mcp.chan).db_name; -        return _mboard(mcp.mboard)[named_prop_t(MBOARD_PROP_TX_DBOARD, db_name)]; +        const std::string name = _tree->list(mb_root(mcp.mboard) / "tx_dsps").at(mcp.chan); +        return mb_root(mcp.mboard) / "tx_dsps" / name;      } -    wax::obj _rx_subdev(size_t chan){ + +    property_tree::path_type rx_rf_fe_root(const size_t chan){          mboard_chan_pair mcp = rx_chan_to_mcp(chan); -        std::string sd_name = get_rx_subdev_spec(mcp.mboard).at(mcp.chan).sd_name; -        return _rx_dboard(chan)[named_prop_t(DBOARD_PROP_SUBDEV, sd_name)]; +        const subdev_spec_pair_t spec = get_rx_subdev_spec(mcp.mboard).at(mcp.chan); +        return mb_root(mcp.mboard) / "dboards" / spec.db_name / "rx_frontends" / spec.sd_name;      } -    wax::obj _tx_subdev(size_t chan){ + +    property_tree::path_type tx_rf_fe_root(const size_t chan){          mboard_chan_pair mcp = tx_chan_to_mcp(chan); -        std::string sd_name = get_tx_subdev_spec(mcp.mboard).at(mcp.chan).sd_name; -        return _tx_dboard(chan)[named_prop_t(DBOARD_PROP_SUBDEV, sd_name)]; +        const subdev_spec_pair_t spec = get_tx_subdev_spec(mcp.mboard).at(mcp.chan); +        return mb_root(mcp.mboard) / "dboards" / spec.db_name / "tx_frontends" / spec.sd_name;      } -    gain_group::sptr _rx_gain_group(size_t chan){ + +    gain_group::sptr rx_gain_group(size_t chan){          mboard_chan_pair mcp = rx_chan_to_mcp(chan); -        std::string sd_name = get_rx_subdev_spec(mcp.mboard).at(mcp.chan).sd_name; -        return _rx_dboard(chan)[named_prop_t(DBOARD_PROP_GAIN_GROUP, sd_name)].as<gain_group::sptr>(); +        const subdev_spec_pair_t spec = get_rx_subdev_spec(mcp.mboard).at(mcp.chan); +        gain_group::sptr gg = gain_group::make(); +        BOOST_FOREACH(const std::string &name, _tree->list(mb_root(mcp.mboard) / "rx_codecs" / spec.db_name / "gains")){ +            gg->register_fcns("ADC-"+name, make_gain_fcns_from_path(_tree, mb_root(mcp.mboard) / "rx_codecs" / spec.db_name / "gains" / name), 0 /* low prio */); +        } +        BOOST_FOREACH(const std::string &name, _tree->list(rx_rf_fe_root(chan) / "gains")){ +            gg->register_fcns(name, make_gain_fcns_from_path(_tree, rx_rf_fe_root(chan) / "gains" / name), 1 /* high prio */); +        } +        return gg;      } -    gain_group::sptr _tx_gain_group(size_t chan){ + +    gain_group::sptr tx_gain_group(size_t chan){          mboard_chan_pair mcp = tx_chan_to_mcp(chan); -        std::string sd_name = get_tx_subdev_spec(mcp.mboard).at(mcp.chan).sd_name; -        return _tx_dboard(chan)[named_prop_t(DBOARD_PROP_GAIN_GROUP, sd_name)].as<gain_group::sptr>(); +        const subdev_spec_pair_t spec = get_tx_subdev_spec(mcp.mboard).at(mcp.chan); +        gain_group::sptr gg = gain_group::make(); +        BOOST_FOREACH(const std::string &name, _tree->list(mb_root(mcp.mboard) / "tx_codecs" / spec.db_name / "gains")){ +            gg->register_fcns("ADC-"+name, make_gain_fcns_from_path(_tree, mb_root(mcp.mboard) / "tx_codecs" / spec.db_name / "gains" / name), 1 /* high prio */); +        } +        BOOST_FOREACH(const std::string &name, _tree->list(tx_rf_fe_root(chan) / "gains")){ +            gg->register_fcns(name, make_gain_fcns_from_path(_tree, tx_rf_fe_root(chan) / "gains" / name), 0 /* low prio */); +        } +        return gg;      }  }; diff --git a/host/lib/usrp/tune_helper.cpp b/host/lib/usrp/tune_helper.cpp deleted file mode 100644 index 264e6c04b..000000000 --- a/host/lib/usrp/tune_helper.cpp +++ /dev/null @@ -1,147 +0,0 @@ -// -// Copyright 2010-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 <uhd/usrp/tune_helper.hpp> -#include <uhd/usrp/subdev_props.hpp> -#include <uhd/usrp/dsp_props.hpp> -#include <uhd/usrp/dboard_iface.hpp> //unit_t -#include <uhd/utils/algorithm.hpp> -#include <cmath> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * Tune Helper Functions - **********************************************************************/ -static tune_result_t tune_xx_subdev_and_dsp( -    dboard_iface::unit_t unit, -    wax::obj subdev, wax::obj dsp, -    const tune_request_t &tune_request -){ -    wax::obj subdev_freq_proxy = subdev[SUBDEV_PROP_FREQ]; -    wax::obj dsp_freq_proxy = dsp[DSP_PROP_FREQ_SHIFT]; - -    //------------------------------------------------------------------ -    //-- calculate the LO offset, only used with automatic policy -    //------------------------------------------------------------------ -    double lo_offset = 0.0; -    if (subdev[SUBDEV_PROP_USE_LO_OFFSET].as<bool>()){ -        //If the local oscillator will be in the passband, use an offset. -        //But constrain the LO offset by the width of the filter bandwidth. -        double rate = dsp[DSP_PROP_HOST_RATE].as<double>(); -        double bw = subdev[SUBDEV_PROP_BANDWIDTH].as<double>(); -        if (bw > rate) lo_offset = std::min((bw - rate)/2, rate/2); -    } - -    //------------------------------------------------------------------ -    //-- set the RF frequency depending upon the policy -    //------------------------------------------------------------------ -    double target_rf_freq = 0.0; -    switch (tune_request.rf_freq_policy){ -    case tune_request_t::POLICY_AUTO: -        target_rf_freq = tune_request.target_freq + lo_offset; -        subdev_freq_proxy = target_rf_freq; -        break; - -    case tune_request_t::POLICY_MANUAL: -        target_rf_freq = tune_request.rf_freq; -        subdev_freq_proxy = target_rf_freq; -        break; - -    case tune_request_t::POLICY_NONE: break; //does not set -    } -    double actual_rf_freq = subdev_freq_proxy.as<double>(); - -    //------------------------------------------------------------------ -    //-- calculate the dsp freq, only used with automatic policy -    //------------------------------------------------------------------ -    double target_dsp_freq = actual_rf_freq - tune_request.target_freq; - -    //invert the sign on the dsp freq given the following conditions -    if (unit == dboard_iface::UNIT_TX) target_dsp_freq *= -1.0; - -    //------------------------------------------------------------------ -    //-- set the dsp frequency depending upon the dsp frequency policy -    //------------------------------------------------------------------ -    switch (tune_request.dsp_freq_policy){ -    case tune_request_t::POLICY_AUTO: -        dsp_freq_proxy = target_dsp_freq; -        break; - -    case tune_request_t::POLICY_MANUAL: -        target_dsp_freq = tune_request.dsp_freq; -        dsp_freq_proxy = target_dsp_freq; -        break; - -    case tune_request_t::POLICY_NONE: break; //does not set -    } -    double actual_dsp_freq = dsp_freq_proxy.as<double>(); - -    //------------------------------------------------------------------ -    //-- load and return the tune result -    //------------------------------------------------------------------ -    tune_result_t tune_result; -    tune_result.target_rf_freq = target_rf_freq; -    tune_result.actual_rf_freq = actual_rf_freq; -    tune_result.target_dsp_freq = target_dsp_freq; -    tune_result.actual_dsp_freq = actual_dsp_freq; -    return tune_result; -} - -static double derive_freq_from_xx_subdev_and_dsp( -    dboard_iface::unit_t unit, wax::obj subdev, wax::obj dsp -){ -    //extract actual dsp and IF frequencies -    double actual_rf_freq = subdev[SUBDEV_PROP_FREQ].as<double>(); -    double actual_dsp_freq = dsp[DSP_PROP_FREQ_SHIFT].as<double>(); - -    //invert the sign on the dsp freq given the following conditions -    if (unit == dboard_iface::UNIT_TX) actual_dsp_freq *= -1.0; - -    return actual_rf_freq - actual_dsp_freq; -} - -/*********************************************************************** - * RX Tune - **********************************************************************/ -tune_result_t usrp::tune_rx_subdev_and_dsp( -    wax::obj subdev, wax::obj ddc, const tune_request_t &tune_request -){ -    return tune_xx_subdev_and_dsp(dboard_iface::UNIT_RX, subdev, ddc, tune_request); -} - -double usrp::derive_freq_from_rx_subdev_and_dsp( -    wax::obj subdev, wax::obj ddc -){ -    return derive_freq_from_xx_subdev_and_dsp(dboard_iface::UNIT_RX, subdev, ddc); -} - -/*********************************************************************** - * TX Tune - **********************************************************************/ -tune_result_t usrp::tune_tx_subdev_and_dsp( -    wax::obj subdev, wax::obj duc, const tune_request_t &tune_request -){ -    return tune_xx_subdev_and_dsp(dboard_iface::UNIT_TX, subdev, duc, tune_request); -} - -double usrp::derive_freq_from_tx_subdev_and_dsp( -    wax::obj subdev, wax::obj duc -){ -    return derive_freq_from_xx_subdev_and_dsp(dboard_iface::UNIT_TX, subdev, duc); -} diff --git a/host/lib/usrp/usrp1/CMakeLists.txt b/host/lib/usrp/usrp1/CMakeLists.txt index c208cfe8c..70bebe502 100644 --- a/host/lib/usrp/usrp1/CMakeLists.txt +++ b/host/lib/usrp/usrp1/CMakeLists.txt @@ -26,20 +26,11 @@ LIBUHD_REGISTER_COMPONENT("USRP1" ENABLE_USRP1 ON "ENABLE_LIBUHD;ENABLE_USB" OFF  IF(ENABLE_USRP1)      LIBUHD_APPEND_SOURCES( -        ${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}/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}/soft_time_ctrl.cpp          ${CMAKE_CURRENT_SOURCE_DIR}/usrp1_iface.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/usrp1_iface.hpp          ${CMAKE_CURRENT_SOURCE_DIR}/usrp1_impl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/usrp1_impl.hpp      )  ENDIF(ENABLE_USRP1) diff --git a/host/lib/usrp/usrp1/clock_ctrl.cpp b/host/lib/usrp/usrp1/clock_ctrl.cpp deleted file mode 100644 index 9edc010dd..000000000 --- a/host/lib/usrp/usrp1/clock_ctrl.cpp +++ /dev/null @@ -1,68 +0,0 @@ -// -// Copyright 2010-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 "clock_ctrl.hpp" -#include <uhd/utils/msg.hpp> -#include <boost/lexical_cast.hpp> -#include <boost/format.hpp> - -using namespace uhd; - -/*********************************************************************** - * Constants - **********************************************************************/ -static const double default_master_clock_rate = 64e6; - -/*********************************************************************** - * Clock Control Implementation - **********************************************************************/ -class usrp1_clock_ctrl_impl : public usrp1_clock_ctrl { -public: -    usrp1_clock_ctrl_impl(usrp1_iface::sptr iface): _iface(iface){ -        this->set_master_clock_freq(default_master_clock_rate); -        try{ -            if (not _iface->mb_eeprom["mcr"].empty()){ -                UHD_MSG(status) << "Read FPGA clock rate from EEPROM setting." << std::endl; -                const double master_clock_rate = boost::lexical_cast<double>(_iface->mb_eeprom["mcr"]); -                UHD_MSG(status) << boost::format("Initializing FPGA clock to %fMHz...") % (master_clock_rate/1e6) << std::endl; -                this->set_master_clock_freq(master_clock_rate); -            } -        } -        catch(const std::exception &e){ -            UHD_MSG(error) << "Error setting FPGA clock rate from EEPROM: " << e.what() << std::endl; -        } -    } - -    void set_master_clock_freq(double freq){ -        _freq = freq; -    } - -    double get_master_clock_freq(void){ -        return _freq; -    } - -private: -    usrp1_iface::sptr _iface; -    double _freq; -}; - -/*********************************************************************** - * Clock Control Make - **********************************************************************/ -usrp1_clock_ctrl::sptr usrp1_clock_ctrl::make(usrp1_iface::sptr iface){ -    return sptr(new usrp1_clock_ctrl_impl(iface)); -} diff --git a/host/lib/usrp/usrp1/clock_ctrl.hpp b/host/lib/usrp/usrp1/clock_ctrl.hpp deleted file mode 100644 index 339d547e6..000000000 --- a/host/lib/usrp/usrp1/clock_ctrl.hpp +++ /dev/null @@ -1,57 +0,0 @@ -// -// Copyright 2010-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_USRP1_CLOCK_CTRL_HPP -#define INCLUDED_USRP1_CLOCK_CTRL_HPP - -#include "usrp1_iface.hpp" -#include <boost/shared_ptr.hpp> -#include <boost/utility.hpp> -#include <vector> - -/*! - * The usrp1 clock control: - * - Setup system clocks. - * - Disable/enable clock lines. - */ -class usrp1_clock_ctrl : boost::noncopyable{ -public: -    typedef boost::shared_ptr<usrp1_clock_ctrl> sptr; - -    /*! -     * Make a new clock control object. -     * \param iface the usrp1 iface object -     * \return the clock control object -     */ -    static sptr make(usrp1_iface::sptr iface); - -    /*! -     * Set the rate of the fpga clock line. -     * Note: does not really set, its all software. -     * \param freq the new clock rate in Hz -     */ -    virtual void set_master_clock_freq(double freq) = 0; - -    /*! -     * Get the rate of the fpga clock line. -     * \return the fpga clock rate in Hz -     */ -    virtual double get_master_clock_freq(void) = 0; - -}; - -#endif /* INCLUDED_USRP1_CLOCK_CTRL_HPP */ diff --git a/host/lib/usrp/usrp1/codec_ctrl.cpp b/host/lib/usrp/usrp1/codec_ctrl.cpp index 448135185..c82569ea3 100644 --- a/host/lib/usrp/usrp1/codec_ctrl.cpp +++ b/host/lib/usrp/usrp1/codec_ctrl.cpp @@ -16,8 +16,6 @@  //  #include "codec_ctrl.hpp" -#include "usrp_commands.h" -#include "clock_ctrl.hpp"  #include "ad9862_regs.hpp"  #include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp> @@ -43,9 +41,7 @@ const gain_range_t usrp1_codec_ctrl::rx_pga_gain_range(0, 20, 1);  class usrp1_codec_ctrl_impl : public usrp1_codec_ctrl {  public:      //structors -    usrp1_codec_ctrl_impl(usrp1_iface::sptr iface, -                          usrp1_clock_ctrl::sptr clock, -                          int spi_slave); +    usrp1_codec_ctrl_impl(spi_iface::sptr iface, int spi_slave);      ~usrp1_codec_ctrl_impl(void);      //aux adc and dac control @@ -53,7 +49,7 @@ public:      void write_aux_dac(aux_dac_t which, double volts);      //duc control -    void set_duc_freq(double freq); +    void set_duc_freq(double freq, double);      void enable_tx_digital(bool enb);      //pga gain control @@ -66,8 +62,7 @@ public:      void bypass_adc_buffers(bool bypass);  private: -    usrp1_iface::sptr _iface; -    usrp1_clock_ctrl::sptr _clock_ctrl; +    spi_iface::sptr _iface;      int _spi_slave;      ad9862_regs_t _ad9862_regs;      void send_reg(boost::uint8_t addr); @@ -80,12 +75,8 @@ private:  /***********************************************************************   * Codec Control Structors   **********************************************************************/ -usrp1_codec_ctrl_impl::usrp1_codec_ctrl_impl(usrp1_iface::sptr iface, -                                             usrp1_clock_ctrl::sptr clock, -                                             int spi_slave) -{ +usrp1_codec_ctrl_impl::usrp1_codec_ctrl_impl(spi_iface::sptr iface, int spi_slave){      _iface = iface; -    _clock_ctrl = clock;      _spi_slave = spi_slave;      //soft reset @@ -381,9 +372,9 @@ double usrp1_codec_ctrl_impl::fine_tune(double codec_rate, double target_freq)      return actual_freq;  } -void usrp1_codec_ctrl_impl::set_duc_freq(double freq) +void usrp1_codec_ctrl_impl::set_duc_freq(double freq, double rate)  { -    double codec_rate = _clock_ctrl->get_master_clock_freq() * 2; +    double codec_rate = rate * 2;      double coarse_freq = coarse_tune(codec_rate, freq);      double fine_freq = fine_tune(codec_rate / 4, freq - coarse_freq); @@ -421,9 +412,8 @@ void usrp1_codec_ctrl_impl::bypass_adc_buffers(bool bypass) {  /***********************************************************************   * Codec Control Make   **********************************************************************/ -usrp1_codec_ctrl::sptr usrp1_codec_ctrl::make(usrp1_iface::sptr iface, -                                              usrp1_clock_ctrl::sptr clock, +usrp1_codec_ctrl::sptr usrp1_codec_ctrl::make(spi_iface::sptr iface,                                                int spi_slave)  { -    return sptr(new usrp1_codec_ctrl_impl(iface, clock, spi_slave)); +    return sptr(new usrp1_codec_ctrl_impl(iface, spi_slave));  } diff --git a/host/lib/usrp/usrp1/codec_ctrl.hpp b/host/lib/usrp/usrp1/codec_ctrl.hpp index 20e4015c5..70f4e0b61 100644 --- a/host/lib/usrp/usrp1/codec_ctrl.hpp +++ b/host/lib/usrp/usrp1/codec_ctrl.hpp @@ -18,8 +18,7 @@  #ifndef INCLUDED_USRP1_CODEC_CTRL_HPP  #define INCLUDED_USRP1_CODEC_CTRL_HPP -#include "usrp1_iface.hpp" -#include "clock_ctrl.hpp" +#include <uhd/types/serial.hpp>  #include <uhd/types/ranges.hpp>  #include <boost/shared_ptr.hpp>  #include <boost/utility.hpp> @@ -38,13 +37,10 @@ public:      /*!       * Make a new clock control object. -     * \param iface the usrp1 iface object +     * \param iface the spi iface object       * \param spi_slave which spi device -     * \return the clock control object       */ -    static sptr make(usrp1_iface::sptr iface, -        usrp1_clock_ctrl::sptr clock, int spi_slave -    ); +    static sptr make(uhd::spi_iface::sptr iface, int spi_slave);      //! aux adc identifier constants      enum aux_adc_t{ @@ -91,7 +87,7 @@ public:      virtual double get_rx_pga_gain(char which) = 0;      //! Set the TX modulator frequency -    virtual void set_duc_freq(double freq) = 0; +    virtual void set_duc_freq(double freq, double rate) = 0;      //! Enable or disable the digital part of the DAC      virtual void enable_tx_digital(bool enb) = 0; diff --git a/host/lib/usrp/usrp1/codec_impl.cpp b/host/lib/usrp/usrp1/codec_impl.cpp deleted file mode 100644 index 7e4032131..000000000 --- a/host/lib/usrp/usrp1/codec_impl.cpp +++ /dev/null @@ -1,159 +0,0 @@ -// -// Copyright 2010-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 "usrp1_impl.hpp" -#include <uhd/exception.hpp> -#include <uhd/usrp/codec_props.hpp> -#include <boost/bind.hpp> -#include <boost/foreach.hpp> -#include <boost/format.hpp> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * Helper Methods - **********************************************************************/ -void usrp1_impl::codec_init(void) -{ -    //make proxies -    BOOST_FOREACH(dboard_slot_t dboard_slot, _dboard_slots){ -        _rx_codec_proxies[dboard_slot] = wax_obj_proxy::make( -              boost::bind(&usrp1_impl::rx_codec_get, this, _1, _2, dboard_slot), -              boost::bind(&usrp1_impl::rx_codec_set, this, _1, _2, dboard_slot)); - -        _tx_codec_proxies[dboard_slot] = wax_obj_proxy::make( -              boost::bind(&usrp1_impl::tx_codec_get, this, _1, _2, dboard_slot), -              boost::bind(&usrp1_impl::tx_codec_set, this, _1, _2, dboard_slot)); -    } -}     - -/*********************************************************************** - * RX Codec Properties - **********************************************************************/ -static const std::string adc_pga_gain_name = "PGA"; - -void usrp1_impl::rx_codec_get(const wax::obj &key_, wax::obj &val, dboard_slot_t dboard_slot) -{ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<codec_prop_t>()) { -    case CODEC_PROP_NAME: -        val = str(boost::format("usrp1 adc - ad9862 - slot %c") % char(dboard_slot)); -        return; - -    case CODEC_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case CODEC_PROP_GAIN_NAMES: -        val = prop_names_t(1, adc_pga_gain_name); -        return; - -    case CODEC_PROP_GAIN_RANGE: -        UHD_ASSERT_THROW(key.name == adc_pga_gain_name); -        val = usrp1_codec_ctrl::rx_pga_gain_range; -        return; - -    case CODEC_PROP_GAIN_I: -        UHD_ASSERT_THROW(key.name == adc_pga_gain_name); -        val = _codec_ctrls[dboard_slot]->get_rx_pga_gain('A'); -        return; - -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == adc_pga_gain_name); -        val = _codec_ctrls[dboard_slot]->get_rx_pga_gain('B'); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void usrp1_impl::rx_codec_set(const wax::obj &key_, const wax::obj &val, dboard_slot_t dboard_slot) -{ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the set request conditioned on the key -    switch(key.as<codec_prop_t>()) { -    case CODEC_PROP_GAIN_I: -        UHD_ASSERT_THROW(key.name == adc_pga_gain_name); -        _codec_ctrls[dboard_slot]->set_rx_pga_gain(val.as<double>(), 'A'); -        return; - -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == adc_pga_gain_name); -        _codec_ctrls[dboard_slot]->set_rx_pga_gain(val.as<double>(), 'B'); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} - -/*********************************************************************** - * TX Codec Properties - **********************************************************************/ -static const std::string dac_pga_gain_name = "PGA"; - -void usrp1_impl::tx_codec_get(const wax::obj &key_, wax::obj &val, dboard_slot_t dboard_slot) -{ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<codec_prop_t>()) { -    case CODEC_PROP_NAME: -        val = str(boost::format("usrp1 dac - ad9862 - slot %c") % char(dboard_slot)); -        return; - -    case CODEC_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case CODEC_PROP_GAIN_NAMES: -        val = prop_names_t(1, dac_pga_gain_name); -        return; - -    case CODEC_PROP_GAIN_RANGE: -        UHD_ASSERT_THROW(key.name == dac_pga_gain_name); -        val = usrp1_codec_ctrl::tx_pga_gain_range; -        return; - -    case CODEC_PROP_GAIN_I: //only one gain for I and Q -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == dac_pga_gain_name); -        val = _codec_ctrls[dboard_slot]->get_tx_pga_gain(); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void usrp1_impl::tx_codec_set(const wax::obj &key_, const wax::obj &val, dboard_slot_t dboard_slot) -{ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the set request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_GAIN_I: //only one gain for I and Q -    case CODEC_PROP_GAIN_Q: -        UHD_ASSERT_THROW(key.name == dac_pga_gain_name); -        _codec_ctrls[dboard_slot]->set_tx_pga_gain(val.as<double>()); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/usrp1/dboard_iface.cpp b/host/lib/usrp/usrp1/dboard_iface.cpp index 3f3a98b7a..449ec64fe 100644 --- a/host/lib/usrp/usrp1/dboard_iface.cpp +++ b/host/lib/usrp/usrp1/dboard_iface.cpp @@ -20,7 +20,6 @@  #include "fpga_regs_common.h"  #include "usrp_spi_defs.h"  #include "fpga_regs_standard.h" -#include "clock_ctrl.hpp"  #include "codec_ctrl.hpp"  #include <uhd/usrp/dboard_iface.hpp>  #include <uhd/types/dict.hpp> @@ -38,16 +37,16 @@ class usrp1_dboard_iface : public dboard_iface {  public:      usrp1_dboard_iface(usrp1_iface::sptr iface, -                       usrp1_clock_ctrl::sptr clock,                         usrp1_codec_ctrl::sptr codec,                         usrp1_impl::dboard_slot_t dboard_slot, +                       const double master_clock_rate,                         const dboard_id_t &rx_dboard_id      ):          _dboard_slot(dboard_slot), +        _master_clock_rate(master_clock_rate),          _rx_dboard_id(rx_dboard_id)      {          _iface = iface; -        _clock = clock;          _codec = codec;          //init the clock rate shadows @@ -103,24 +102,24 @@ public:  private:      usrp1_iface::sptr _iface; -    usrp1_clock_ctrl::sptr _clock;      usrp1_codec_ctrl::sptr _codec;      uhd::dict<unit_t, double> _clock_rates;      const usrp1_impl::dboard_slot_t _dboard_slot; -    const dboard_id_t &_rx_dboard_id; +    const double _master_clock_rate; +    const dboard_id_t _rx_dboard_id;  };  /***********************************************************************   * Make Function   **********************************************************************/  dboard_iface::sptr usrp1_impl::make_dboard_iface(usrp1_iface::sptr iface, -                                           usrp1_clock_ctrl::sptr clock,                                             usrp1_codec_ctrl::sptr codec, -                                           dboard_slot_t dboard_slot, +                                           usrp1_impl::dboard_slot_t dboard_slot, +                                           const double master_clock_rate,                                             const dboard_id_t &rx_dboard_id  ){      return dboard_iface::sptr(new usrp1_dboard_iface( -        iface, clock, codec, dboard_slot, rx_dboard_id +        iface, codec, dboard_slot, master_clock_rate, rx_dboard_id      ));  } @@ -141,7 +140,7 @@ void usrp1_dboard_iface::set_clock_rate(unit_t unit, double rate)      _clock_rates[unit] = rate;      if (unit == UNIT_RX && _rx_dboard_id == dbsrx_classic_id){ -        size_t divider = size_t(_clock->get_master_clock_freq()/rate); +        size_t divider = size_t(_master_clock_rate/rate);          switch(_dboard_slot){          case usrp1_impl::DBOARD_SLOT_A:              _iface->poke32(FR_RX_A_REFCLK, (divider & 0x7f) | 0x80); @@ -159,10 +158,10 @@ std::vector<double> usrp1_dboard_iface::get_clock_rates(unit_t unit)      std::vector<double> rates;      if (unit == UNIT_RX && _rx_dboard_id == dbsrx_classic_id){          for (size_t div = 1; div <= 127; div++) -            rates.push_back(_clock->get_master_clock_freq() / div); +            rates.push_back(_master_clock_rate / div);      }      else{ -        rates.push_back(_clock->get_master_clock_freq()); +        rates.push_back(_master_clock_rate);      }      return rates;  } @@ -178,7 +177,7 @@ void usrp1_dboard_iface::set_clock_enabled(unit_t, bool)  }  double usrp1_dboard_iface::get_codec_rate(unit_t){ -    return _clock->get_master_clock_freq(); +    return _master_clock_rate;  }  /*********************************************************************** diff --git a/host/lib/usrp/usrp1/dboard_impl.cpp b/host/lib/usrp/usrp1/dboard_impl.cpp deleted file mode 100644 index df0bb6261..000000000 --- a/host/lib/usrp/usrp1/dboard_impl.cpp +++ /dev/null @@ -1,218 +0,0 @@ -// -// Copyright 2010-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 "usrp1_impl.hpp" -#include "usrp_i2c_addr.h" -#include <uhd/usrp/dsp_utils.hpp> -#include <uhd/usrp/misc_utils.hpp> -#include <uhd/exception.hpp> -#include <uhd/usrp/dboard_props.hpp> -#include <uhd/usrp/subdev_props.hpp> -#include <boost/bind.hpp> -#include <boost/foreach.hpp> -#include <boost/format.hpp> -#include <iostream> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * Helper Functions - **********************************************************************/ -static boost::uint8_t get_rx_ee_addr(usrp1_impl::dboard_slot_t dboard_slot){ -    switch(dboard_slot){ -    case usrp1_impl::DBOARD_SLOT_A: return I2C_ADDR_RX_A; -    case usrp1_impl::DBOARD_SLOT_B: return I2C_ADDR_RX_B; -    default: UHD_THROW_INVALID_CODE_PATH(); -    } -} - -static boost::uint8_t get_tx_ee_addr(usrp1_impl::dboard_slot_t dboard_slot){ -    switch(dboard_slot){ -    case usrp1_impl::DBOARD_SLOT_A: return I2C_ADDR_TX_A; -    case usrp1_impl::DBOARD_SLOT_B: return I2C_ADDR_TX_B; -    default: UHD_THROW_INVALID_CODE_PATH(); -    } -} - -/*********************************************************************** - * Dboard Initialization - **********************************************************************/ -void usrp1_impl::dboard_init(void) -{ -    BOOST_FOREACH(dboard_slot_t dboard_slot, _dboard_slots){ - -        //read the tx and rx dboard eeproms -        _rx_db_eeproms[dboard_slot].load(*_iface, get_rx_ee_addr(dboard_slot)); -        _tx_db_eeproms[dboard_slot].load(*_iface, get_tx_ee_addr(dboard_slot)); -        _gdb_eeproms[dboard_slot].load(*_iface, get_tx_ee_addr(dboard_slot) ^ 5); - -        //create a new dboard interface and manager -        _dboard_ifaces[dboard_slot] = make_dboard_iface( -            _iface, _clock_ctrl, _codec_ctrls[dboard_slot], -            dboard_slot, _rx_db_eeproms[dboard_slot].id -        ); - -        _dboard_managers[dboard_slot] = dboard_manager::make( -            _rx_db_eeproms[dboard_slot].id, -            ((_gdb_eeproms[dboard_slot].id == dboard_id_t::none())? _tx_db_eeproms[dboard_slot] : _gdb_eeproms[dboard_slot]).id, -            _dboard_ifaces[dboard_slot] -        ); - -        //setup the dboard proxies -        _rx_dboard_proxies[dboard_slot] = wax_obj_proxy::make( -             boost::bind(&usrp1_impl::rx_dboard_get, this, _1, _2, dboard_slot), -             boost::bind(&usrp1_impl::rx_dboard_set, this, _1, _2, dboard_slot)); - -        _tx_dboard_proxies[dboard_slot] = wax_obj_proxy::make( -             boost::bind(&usrp1_impl::tx_dboard_get, this, _1, _2, dboard_slot), -             boost::bind(&usrp1_impl::tx_dboard_set, this, _1, _2, dboard_slot)); -    } - -} - -/*********************************************************************** - * RX Dboard Get - **********************************************************************/ -void usrp1_impl::rx_dboard_get(const wax::obj &key_, wax::obj &val, dboard_slot_t dboard_slot) -{ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_NAME: -        val = str(boost::format("usrp1 dboard (rx unit) - %c") % char(dboard_slot)); -        return; - -    case DBOARD_PROP_SUBDEV: -        val = _dboard_managers[dboard_slot]->get_rx_subdev(key.name); -        return; - -    case DBOARD_PROP_SUBDEV_NAMES: -        val = _dboard_managers[dboard_slot]->get_rx_subdev_names(); -        return; - -    case DBOARD_PROP_DBOARD_EEPROM: -        val = _rx_db_eeproms[dboard_slot]; -        return; - -    case DBOARD_PROP_DBOARD_IFACE: -        val = _dboard_ifaces[dboard_slot]; -        return; - -    case DBOARD_PROP_CODEC: -        val = _rx_codec_proxies[dboard_slot]->get_link(); -        return; - -    case DBOARD_PROP_GAIN_GROUP: -        val = make_gain_group( -            _rx_db_eeproms[dboard_slot].id, -            _dboard_managers[dboard_slot]->get_rx_subdev(key.name), -            _rx_codec_proxies[dboard_slot]->get_link(), -            GAIN_GROUP_POLICY_RX -        ); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * RX Dboard Set - **********************************************************************/ -void usrp1_impl::rx_dboard_set(const wax::obj &key, const wax::obj &val, dboard_slot_t dboard_slot) -{ -    switch(key.as<dboard_prop_t>()) { -    case DBOARD_PROP_DBOARD_EEPROM: -        _rx_db_eeproms[dboard_slot] = val.as<dboard_eeprom_t>(); -        _rx_db_eeproms[dboard_slot].store(*_iface, get_rx_ee_addr(dboard_slot)); -        return; - -    default: -        UHD_THROW_PROP_SET_ERROR(); -    } -} - -/*********************************************************************** - * TX Dboard Get - **********************************************************************/ -void usrp1_impl::tx_dboard_get(const wax::obj &key_, wax::obj &val, dboard_slot_t dboard_slot) -{ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_NAME: -        val = str(boost::format("usrp1 dboard (tx unit) - %c") % char(dboard_slot)); -        return; - -    case DBOARD_PROP_SUBDEV: -        val = _dboard_managers[dboard_slot]->get_tx_subdev(key.name); -        return; - -    case DBOARD_PROP_SUBDEV_NAMES: -        val = _dboard_managers[dboard_slot]->get_tx_subdev_names(); -        return; - -    case DBOARD_PROP_DBOARD_EEPROM: -        val = _tx_db_eeproms[dboard_slot]; -        return; - -    case DBOARD_PROP_GBOARD_EEPROM: -        val = _gdb_eeproms[dboard_slot]; -        return; - -    case DBOARD_PROP_DBOARD_IFACE: -        val = _dboard_ifaces[dboard_slot]; -        return; - -    case DBOARD_PROP_CODEC: -        val = _tx_codec_proxies[dboard_slot]->get_link(); -        return; - -    case DBOARD_PROP_GAIN_GROUP: -        val = make_gain_group( -            _tx_db_eeproms[dboard_slot].id, -            _dboard_managers[dboard_slot]->get_tx_subdev(key.name), -            _tx_codec_proxies[dboard_slot]->get_link(), -            GAIN_GROUP_POLICY_TX -        ); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * TX Dboard Set - **********************************************************************/ -void usrp1_impl::tx_dboard_set(const wax::obj &key, const wax::obj &val, dboard_slot_t dboard_slot) -{ -    switch(key.as<dboard_prop_t>()) { -    case DBOARD_PROP_DBOARD_EEPROM: -        _tx_db_eeproms[dboard_slot] = val.as<dboard_eeprom_t>(); -        _tx_db_eeproms[dboard_slot].store(*_iface, get_tx_ee_addr(dboard_slot)); -        return; - -    case DBOARD_PROP_GBOARD_EEPROM: -        _gdb_eeproms[dboard_slot] = val.as<dboard_eeprom_t>(); -        _gdb_eeproms[dboard_slot].store(*_iface, get_tx_ee_addr(dboard_slot) ^ 5); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/usrp1/dsp_impl.cpp b/host/lib/usrp/usrp1/dsp_impl.cpp deleted file mode 100644 index 0bddc49f0..000000000 --- a/host/lib/usrp/usrp1/dsp_impl.cpp +++ /dev/null @@ -1,222 +0,0 @@ -// -// Copyright 2010-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 "usrp1_impl.hpp" -#include "fpga_regs_standard.h" -#include <uhd/utils/msg.hpp> -#include <uhd/usrp/dsp_utils.hpp> -#include <uhd/usrp/dsp_props.hpp> -#include <boost/bind.hpp> -#include <boost/format.hpp> -#include <boost/lexical_cast.hpp> -#include <boost/assign/list_of.hpp> -#include <cmath> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * RX DDC Initialization - **********************************************************************/ -void usrp1_impl::rx_dsp_init(void) -{ -    for (size_t i = 0; i < this->get_num_ddcs(); i++){ -        _rx_dsp_proxies[str(boost::format("DSP%d")%i)] = wax_obj_proxy::make( -            boost::bind(&usrp1_impl::rx_dsp_get, this, _1, _2, i), -            boost::bind(&usrp1_impl::rx_dsp_set, this, _1, _2, i) -        ); -        rx_dsp_set(DSP_PROP_HOST_RATE, _clock_ctrl->get_master_clock_freq() / 16, i); -    } -} - -/*********************************************************************** - * RX DDC Get - **********************************************************************/ -void usrp1_impl::rx_dsp_get(const wax::obj &key_, wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ -    case DSP_PROP_NAME: -        val = str(boost::format("usrp1 ddc%d %s") -            % which_dsp -            % (this->has_rx_halfband()? "+ hb" : "") -        ); -        return; - -    case DSP_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case DSP_PROP_FREQ_SHIFT: -        val = _rx_dsp_freqs[which_dsp]; -        return; - -    case DSP_PROP_CODEC_RATE: -        val = _clock_ctrl->get_master_clock_freq(); -        return; - -    case DSP_PROP_HOST_RATE: -        val = _clock_ctrl->get_master_clock_freq()/_rx_dsp_decim; -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } - -} - -/*********************************************************************** - * RX DDC Set - **********************************************************************/ -void usrp1_impl::rx_dsp_set(const wax::obj &key_, const wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()) { -    case DSP_PROP_FREQ_SHIFT: { -            double new_freq = val.as<double>(); -            boost::uint32_t reg_word = dsp_type1::calc_cordic_word_and_update( -                new_freq, _clock_ctrl->get_master_clock_freq()); - -            static const boost::uint32_t dsp_index_to_reg_val[4] = { -                FR_RX_FREQ_0, FR_RX_FREQ_1, FR_RX_FREQ_2, FR_RX_FREQ_3 -            }; -            _iface->poke32(dsp_index_to_reg_val[which_dsp], ~reg_word + 1); -            _rx_dsp_freqs[which_dsp] = new_freq; -            return; -        } - -    case DSP_PROP_HOST_RATE: -        if (which_dsp != 0) return; //only for dsp[0] as this is vectorized -        { -            size_t rate = size_t(_clock_ctrl->get_master_clock_freq() / val.as<double>()); - -            //clip the rate to something in range: -            rate = std::min<size_t>(std::max<size_t>(rate, 4), 256); - -            _rx_dsp_decim = rate; -            //TODO Poll every 100ms. Make it selectable? -            _rx_samps_per_poll_interval = size_t(0.1 * _clock_ctrl->get_master_clock_freq() / rate); - -            bool s = this->disable_rx(); -            _iface->poke32(FR_DECIM_RATE, _rx_dsp_decim/2 - 1); -            this->restore_rx(s); -        } -        this->update_xport_channel_mapping(); //rate changed -> update -        return; - -    case DSP_PROP_STREAM_CMD: -        if (which_dsp != 0) return; //only for dsp[0] as this is vectorized -        _soft_time_ctrl->issue_stream_cmd(val.as<stream_cmd_t>()); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } - -} - -/*********************************************************************** - * TX DUC Initialization - **********************************************************************/ -void usrp1_impl::tx_dsp_init(void) -{ -    for (size_t i = 0; i < this->get_num_ducs(); i++){ -        _tx_dsp_proxies[str(boost::format("DSP%d")%i)] = wax_obj_proxy::make( -            boost::bind(&usrp1_impl::tx_dsp_get, this, _1, _2, i), -            boost::bind(&usrp1_impl::tx_dsp_set, this, _1, _2, i) -        ); -        tx_dsp_set(DSP_PROP_HOST_RATE, _clock_ctrl->get_master_clock_freq() / 16, i); -    } -} - -/*********************************************************************** - * TX DUC Get - **********************************************************************/ -void usrp1_impl::tx_dsp_get(const wax::obj &key_, wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()) { -    case DSP_PROP_NAME: -        val = str(boost::format("usrp1 duc%d %s") -            % which_dsp -            % (this->has_tx_halfband()? "+ hb" : "") -        ); -        return; - -    case DSP_PROP_OTHERS: -        val = prop_names_t(); //empty -        return; - -    case DSP_PROP_FREQ_SHIFT: -        val = _tx_dsp_freqs[which_dsp]; -        return; - -    case DSP_PROP_CODEC_RATE: -        val = _clock_ctrl->get_master_clock_freq(); -        return; - -    case DSP_PROP_HOST_RATE: -        val = _clock_ctrl->get_master_clock_freq() / _tx_dsp_interp; -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } - -} - -/*********************************************************************** - * TX DUC Set - **********************************************************************/ -void usrp1_impl::tx_dsp_set(const wax::obj &key_, const wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()) { - -    case DSP_PROP_FREQ_SHIFT: { -            double new_freq = val.as<double>(); - -            //map the freq shift key to a subdev spec to a particular codec chip -            std::string db_name = _tx_subdev_spec.at(which_dsp).db_name; -            if (db_name == "A") _codec_ctrls[DBOARD_SLOT_A]->set_duc_freq(new_freq); -            if (db_name == "B") _codec_ctrls[DBOARD_SLOT_B]->set_duc_freq(new_freq); - -            _tx_dsp_freqs[which_dsp] = new_freq; -            return; -        } - -    case DSP_PROP_HOST_RATE: -        if (which_dsp != 0) return; //only for dsp[0] as this is vectorized -        { -            size_t rate = size_t(_clock_ctrl->get_master_clock_freq() / val.as<double>()); - -            //clip the rate to something in range: -            rate = std::min<size_t>(std::max<size_t>(rate, 4), 256); - -            _tx_dsp_interp = rate; - -            //TODO Poll every 100ms. Make it selectable?  -            _tx_samps_per_poll_interval = size_t(0.1 * _clock_ctrl->get_master_clock_freq() / rate); - -            bool s = this->disable_tx(); -            _iface->poke32(FR_INTERP_RATE, _tx_dsp_interp/2 - 1); -            this->restore_tx(s); -        } -        this->update_xport_channel_mapping(); //rate changed -> update -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } - -} diff --git a/host/lib/usrp/usrp1/io_impl.cpp b/host/lib/usrp/usrp1/io_impl.cpp index 90ed17cd8..b596bbd04 100644 --- a/host/lib/usrp/usrp1/io_impl.cpp +++ b/host/lib/usrp/usrp1/io_impl.cpp @@ -15,26 +15,26 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // +#include "validate_subdev_spec.hpp"  #define SRPH_DONT_CHECK_SEQUENCE  #include "../../transport/super_recv_packet_handler.hpp"  #include "../../transport/super_send_packet_handler.hpp" +#include "usrp1_calc_mux.hpp" +#include "fpga_regs_standard.h"  #include "usrp_commands.h"  #include "usrp1_impl.hpp"  #include <uhd/utils/msg.hpp>  #include <uhd/utils/safe_call.hpp> -#include <uhd/utils/thread_priority.hpp> -#include <uhd/usrp/dsp_props.hpp>  #include <uhd/transport/bounded_buffer.hpp> +#include <boost/math/special_functions/sign.hpp> +#include <boost/math/special_functions/round.hpp> +#include <boost/thread/thread.hpp>  #include <boost/bind.hpp>  #include <boost/format.hpp> -#include <boost/asio.hpp> -#include <boost/bind.hpp> -#include <boost/thread.hpp>  using namespace uhd;  using namespace uhd::usrp;  using namespace uhd::transport; -namespace asio = boost::asio;  static const size_t alignment_padding = 512; @@ -124,8 +124,6 @@ static void usrp1_bs_vrt_unpacker(  struct usrp1_impl::io_impl{      io_impl(zero_copy_if::sptr data_transport):          data_transport(data_transport), -        underflow_poll_samp_count(0), -        overflow_poll_samp_count(0),          curr_buff(offset_send_buffer(data_transport->get_send_buff())),          omsb(boost::bind(&usrp1_impl::io_impl::commit_send_buff, this, _1, _2, _3))      { @@ -133,6 +131,8 @@ struct usrp1_impl::io_impl{      }      ~io_impl(void){ +        vandal_tribe.interrupt_all(); +        vandal_tribe.join_all();          UHD_SAFE_CALL(flush_send_buff();)      } @@ -142,10 +142,6 @@ struct usrp1_impl::io_impl{      sph::recv_packet_handler recv_handler;      sph::send_packet_handler send_handler; -    //state management for overflow and underflow -    size_t underflow_poll_samp_count; -    size_t overflow_poll_samp_count; -      //wrapper around the actual send buffer interface      //all of this to ensure only aligned lengths are committed      //NOTE: you must commit before getting a new buffer @@ -162,6 +158,9 @@ struct usrp1_impl::io_impl{          //make a new managed buffer with the offset buffs          return omsb.get_new(curr_buff, next_buff);      } + +    boost::thread_group vandal_tribe; +    boost::system_time last_send_time;  };  /*! @@ -230,51 +229,223 @@ void usrp1_impl::io_init(void){      _io_impl = UHD_PIMPL_MAKE(io_impl, (_data_transport)); -    _soft_time_ctrl = soft_time_ctrl::make( -        boost::bind(&usrp1_impl::rx_stream_on_off, this, _1) -    ); - -    this->enable_tx(true); //always enabled -    rx_stream_on_off(false); -    _io_impl->flush_send_buff(); - -    //update mapping here since it didnt b4 when io init not called first -    update_xport_channel_mapping(); -} - -void usrp1_impl::update_xport_channel_mapping(void){ -    if (_io_impl.get() == NULL) return; //not inited yet +    //create a new vandal thread to poll xerflow conditions +    boost::barrier spawn_barrier(2); +    _io_impl->vandal_tribe.create_thread(boost::bind( +        &usrp1_impl::vandal_conquest_loop, +        this, boost::ref(spawn_barrier) +    )); +    spawn_barrier.wait(); -    //set all of the relevant properties on the handler -    boost::mutex::scoped_lock recv_lock = _io_impl->recv_handler.get_scoped_lock(); +    //init some handler stuff +    _io_impl->recv_handler.set_tick_rate(_master_clock_rate);      _io_impl->recv_handler.set_vrt_unpacker(&usrp1_bs_vrt_unpacker); -    _io_impl->recv_handler.set_tick_rate(_clock_ctrl->get_master_clock_freq()); -    _io_impl->recv_handler.set_samp_rate(_rx_dsp_proxies[_rx_dsp_proxies.keys().at(0)]->get_link()[DSP_PROP_HOST_RATE].as<double>());      _io_impl->recv_handler.set_xport_chan_get_buff(0, boost::bind(          &uhd::transport::zero_copy_if::get_recv_buff, _io_impl->data_transport, _1      )); -    _io_impl->recv_handler.set_converter(_rx_otw_type, _rx_subdev_spec.size()); - -    //set all of the relevant properties on the handler -    boost::mutex::scoped_lock send_lock = _io_impl->send_handler.get_scoped_lock(); +    _io_impl->send_handler.set_tick_rate(_master_clock_rate);      _io_impl->send_handler.set_vrt_packer(&usrp1_bs_vrt_packer); -    _io_impl->send_handler.set_tick_rate(_clock_ctrl->get_master_clock_freq()); -    _io_impl->send_handler.set_samp_rate(_tx_dsp_proxies[_tx_dsp_proxies.keys().at(0)]->get_link()[DSP_PROP_HOST_RATE].as<double>());      _io_impl->send_handler.set_xport_chan_get_buff(0, boost::bind(          &usrp1_impl::io_impl::get_send_buff, _io_impl.get(), _1      )); -    _io_impl->send_handler.set_converter(_tx_otw_type, _tx_subdev_spec.size()); -    _io_impl->send_handler.set_max_samples_per_packet(get_max_send_samps_per_packet()); + +    //init as disabled, then call the real function (uses restore) +    this->enable_rx(false); +    this->enable_tx(false); +    rx_stream_on_off(false); +    tx_stream_on_off(false); +    _io_impl->flush_send_buff();  }  void usrp1_impl::rx_stream_on_off(bool enb){ -    this->enable_rx(enb); +    this->restore_rx(enb);      //drain any junk in the receive transport after stop streaming command      while(not enb and _data_transport->get_recv_buff().get() != NULL){          /* NOP */      }  } +void usrp1_impl::tx_stream_on_off(bool enb){ +    _io_impl->last_send_time = boost::get_system_time(); +    if (_tx_enabled and not enb) _io_impl->flush_send_buff(); +    this->restore_tx(enb); +} + +/*! + * Casually poll the overflow and underflow registers. + * On an underflow, push an async message into the queue and print. + * On an overflow, interleave an inline message into recv and print. + * This procedure creates "soft" inline and async user messages. + */ +void usrp1_impl::vandal_conquest_loop(boost::barrier &spawn_barrier){ +    spawn_barrier.wait(); + +    //initialize the async metadata +    async_metadata_t async_metadata; +    async_metadata.channel = 0; +    async_metadata.has_time_spec = true; +    async_metadata.event_code = async_metadata_t::EVENT_CODE_UNDERFLOW; + +    //initialize the inline metadata +    rx_metadata_t inline_metadata; +    inline_metadata.has_time_spec = true; +    inline_metadata.error_code = rx_metadata_t::ERROR_CODE_OVERFLOW; + +    //start the polling loop... +    try{ while (not boost::this_thread::interruption_requested()){ +        boost::uint8_t underflow = 0, overflow = 0; + +        //shutoff transmit if it has been too long since send() was called +        if (_tx_enabled and (boost::get_system_time() - _io_impl->last_send_time) > boost::posix_time::milliseconds(100)){ +            this->tx_stream_on_off(false); +        } + +        //always poll regardless of enabled so we can clear the conditions +        _fx2_ctrl->usrp_control_read( +            VRQ_GET_STATUS, 0, GS_TX_UNDERRUN, &underflow, sizeof(underflow) +        ); +        _fx2_ctrl->usrp_control_read( +            VRQ_GET_STATUS, 0, GS_RX_OVERRUN, &overflow, sizeof(overflow) +        ); + +        //handle message generation for xerflow conditions +        if (_tx_enabled and underflow){ +            async_metadata.time_spec = _soft_time_ctrl->get_time(); +            _soft_time_ctrl->get_async_queue().push_with_pop_on_full(async_metadata); +            UHD_MSG(fastpath) << "U"; +        } +        if (_rx_enabled and overflow){ +            inline_metadata.time_spec = _soft_time_ctrl->get_time(); +            _soft_time_ctrl->get_inline_queue().push_with_pop_on_full(inline_metadata); +            UHD_MSG(fastpath) << "O"; +        } + +        boost::this_thread::sleep(boost::posix_time::milliseconds(50)); +    }} +    catch(const boost::thread_interrupted &){} //normal exit condition +    catch(const std::exception &e){ +        UHD_MSG(error) << "The vandal caught an unexpected exception " << e.what() << std::endl; +    } +} + +/*********************************************************************** + * Properties callback methods below + **********************************************************************/ +void usrp1_impl::update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){ +    boost::mutex::scoped_lock lock = _io_impl->recv_handler.get_scoped_lock(); + +    //sanity checking +    validate_subdev_spec(_tree, spec, "rx"); + +    _rx_subdev_spec = spec; //shadow +    _io_impl->recv_handler.resize(spec.size()); +    _io_impl->recv_handler.set_converter(_rx_otw_type, spec.size()); + +    //set the mux and set the number of rx channels +    std::vector<mapping_pair_t> mapping; +    BOOST_FOREACH(const subdev_spec_pair_t &pair, spec){ +        const std::string conn = _tree->access<std::string>(str(boost::format( +            "/mboards/0/dboards/%s/rx_frontends/%s/connection" +        ) % pair.db_name % pair.sd_name)).get(); +        mapping.push_back(std::make_pair(pair.db_name, conn)); +    } +    bool s = this->disable_rx(); +    _iface->poke32(FR_RX_MUX, calc_rx_mux(mapping)); +    this->restore_rx(s); +} + +void usrp1_impl::update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){ +    boost::mutex::scoped_lock lock = _io_impl->send_handler.get_scoped_lock(); + +    //sanity checking +    validate_subdev_spec(_tree, spec, "tx"); + +    _tx_subdev_spec = spec; //shadow +    _io_impl->send_handler.resize(spec.size()); +    _io_impl->send_handler.set_converter(_tx_otw_type, spec.size()); + +    //set the mux and set the number of tx channels +    std::vector<mapping_pair_t> mapping; +    BOOST_FOREACH(const subdev_spec_pair_t &pair, spec){ +        const std::string conn = _tree->access<std::string>(str(boost::format( +            "/mboards/0/dboards/%s/tx_frontends/%s/connection" +        ) % pair.db_name % pair.sd_name)).get(); +        mapping.push_back(std::make_pair(pair.db_name, conn)); +    } +    bool s = this->disable_tx(); +    _iface->poke32(FR_TX_MUX, calc_tx_mux(mapping)); +    this->restore_tx(s); + +    //if the spec changes size, so does the max samples per packet... +    _io_impl->send_handler.set_max_samples_per_packet(get_max_send_samps_per_packet()); +} + +double usrp1_impl::update_rx_samp_rate(const double samp_rate){ +    boost::mutex::scoped_lock lock = _io_impl->recv_handler.get_scoped_lock(); + +    const size_t rate = uhd::clip<size_t>( +        boost::math::iround(_master_clock_rate / samp_rate), size_t(std::ceil(_master_clock_rate / 8e6)), 256 +    ); + +    bool s = this->disable_rx(); +    _iface->poke32(FR_DECIM_RATE, rate/2 - 1); +    this->restore_rx(s); + +    _io_impl->recv_handler.set_samp_rate(_master_clock_rate / rate); +    return _master_clock_rate / rate; +} + +double usrp1_impl::update_tx_samp_rate(const double samp_rate){ +    boost::mutex::scoped_lock lock = _io_impl->send_handler.get_scoped_lock(); + +    const size_t rate = uhd::clip<size_t>( +        boost::math::iround(_master_clock_rate / samp_rate), size_t(std::ceil(_master_clock_rate / 8e6)), 256 +    ); + +    bool s = this->disable_tx(); +    _iface->poke32(FR_INTERP_RATE, rate/2 - 1); +    this->restore_tx(s); + +    _io_impl->send_handler.set_samp_rate(_master_clock_rate / rate); +    return _master_clock_rate / rate; +} + +double usrp1_impl::update_rx_dsp_freq(const size_t dspno, const double freq_){ + +    //correct for outside of rate (wrap around) +    double freq = std::fmod(freq_, _master_clock_rate); +    if (std::abs(freq) > _master_clock_rate/2.0) +        freq -= boost::math::sign(freq)*_master_clock_rate; + +    //calculate the freq register word (signed) +    UHD_ASSERT_THROW(std::abs(freq) <= _master_clock_rate/2.0); +    static const double scale_factor = std::pow(2.0, 32); +    const boost::int32_t freq_word = boost::int32_t(boost::math::round((freq / _master_clock_rate) * scale_factor)); + +    static const boost::uint32_t dsp_index_to_reg_val[4] = { +        FR_RX_FREQ_0, FR_RX_FREQ_1, FR_RX_FREQ_2, FR_RX_FREQ_3 +    }; +    _iface->poke32(dsp_index_to_reg_val[dspno], ~freq_word + 1); + +    return (double(freq_word) / scale_factor) * _master_clock_rate; +} + +double usrp1_impl::update_tx_dsp_freq(const size_t dspno, const double freq){ +    //map the freq shift key to a subdev spec to a particular codec chip +    _dbc[_tx_subdev_spec.at(dspno).db_name].codec->set_duc_freq(freq, _master_clock_rate); +    return freq; //assume infinite precision +} + +/*********************************************************************** + * Async Data + **********************************************************************/ +bool usrp1_impl::recv_async_msg( +    async_metadata_t &async_metadata, double timeout +){ +    boost::this_thread::disable_interruption di; //disable because the wait can throw +    return _soft_time_ctrl->get_async_queue().pop_with_timed_wait(async_metadata, timeout); +} +  /***********************************************************************   * Data send + helper functions   **********************************************************************/ @@ -292,29 +463,23 @@ size_t usrp1_impl::send(  ){      if (_soft_time_ctrl->send_pre(metadata, timeout)) return 0; +    this->tx_stream_on_off(true); //always enable (it will do the right thing)      size_t num_samps_sent = _io_impl->send_handler.send(          buffs, nsamps_per_buff,          metadata, io_type,          send_mode, timeout      ); -    //handle eob flag (commit the buffer, disable the DACs) +    //handle eob flag (commit the buffer, /*disable the DACs*/)      //check num samps sent to avoid flush on incomplete/timeout      if (metadata.end_of_burst and num_samps_sent == nsamps_per_buff){ -        _io_impl->flush_send_buff(); -    } - -    //handle the polling for underflow conditions -    _io_impl->underflow_poll_samp_count += num_samps_sent; -    if (_io_impl->underflow_poll_samp_count >= _tx_samps_per_poll_interval){ -        _io_impl->underflow_poll_samp_count = 0; //reset count -        boost::uint8_t underflow = 0; -        ssize_t ret = _ctrl_transport->usrp_control_read( -            VRQ_GET_STATUS, 0, GS_TX_UNDERRUN, -            &underflow, sizeof(underflow) -        ); -        if (ret < 0)        UHD_MSG(error) << "USRP: underflow check failed" << std::endl; -        else if (underflow) UHD_MSG(fastpath) << "U"; +        async_metadata_t metadata; +        metadata.channel = 0; +        metadata.has_time_spec = true; +        metadata.time_spec = _soft_time_ctrl->get_time(); +        metadata.event_code = async_metadata_t::EVENT_CODE_BURST_ACK; +        _soft_time_ctrl->get_async_queue().push_with_pop_on_full(metadata); +        this->tx_stream_on_off(false);      }      return num_samps_sent; @@ -335,26 +500,14 @@ size_t usrp1_impl::recv(      rx_metadata_t &metadata, const io_type_t &io_type,      recv_mode_t recv_mode, double timeout  ){ +    //interleave a "soft" inline message into the receive stream: +    if (_soft_time_ctrl->get_inline_queue().pop_with_haste(metadata)) return 0; +      size_t num_samps_recvd = _io_impl->recv_handler.recv(          buffs, nsamps_per_buff,          metadata, io_type,          recv_mode, timeout      ); -    _soft_time_ctrl->recv_post(metadata, num_samps_recvd); - -    //handle the polling for overflow conditions -    _io_impl->overflow_poll_samp_count += num_samps_recvd; -    if (_io_impl->overflow_poll_samp_count >= _rx_samps_per_poll_interval){ -        _io_impl->overflow_poll_samp_count = 0; //reset count -        boost::uint8_t overflow = 0; -        ssize_t ret = _ctrl_transport->usrp_control_read( -            VRQ_GET_STATUS, 0, GS_RX_OVERRUN, -            &overflow, sizeof(overflow) -        ); -        if (ret < 0)       UHD_MSG(error) << "USRP: overflow check failed" << std::endl; -        else if (overflow) UHD_MSG(fastpath) << "O"; -    } - -    return num_samps_recvd; +    return _soft_time_ctrl->recv_post(metadata, num_samps_recvd);  } diff --git a/host/lib/usrp/usrp1/mboard_impl.cpp b/host/lib/usrp/usrp1/mboard_impl.cpp deleted file mode 100644 index a265a5089..000000000 --- a/host/lib/usrp/usrp1/mboard_impl.cpp +++ /dev/null @@ -1,407 +0,0 @@ -// -// Copyright 2010-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 "usrp1_impl.hpp" -#include "usrp_commands.h" -#include "fpga_regs_standard.h" -#include "fpga_regs_common.h" -#include "usrp_i2c_addr.h" -#include <uhd/utils/msg.hpp> -#include <uhd/utils/log.hpp> -#include <uhd/usrp/misc_utils.hpp> -#include <uhd/usrp/mboard_props.hpp> -#include <uhd/usrp/dboard_props.hpp> -#include <uhd/usrp/subdev_props.hpp> -#include <uhd/utils/msg.hpp> -#include <uhd/utils/assert_has.hpp> -#include <uhd/utils/images.hpp> -#include <boost/assign/list_of.hpp> -#include <boost/foreach.hpp> -#include <boost/bind.hpp> -#include <boost/thread/thread.hpp> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * Calculate the RX mux value: - *    The I and Q mux values are intentionally reversed to flip I and Q - *    to account for the reversal in the type conversion routines. - **********************************************************************/ -static int calc_rx_mux_pair(int adc_for_i, int adc_for_q){ -    return (adc_for_i << 2) | (adc_for_q << 0); //shift reversal here -} - -/*! - *    3                   2                   1                   0 - *  1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 - * +-----------------------+-------+-------+-------+-------+-+-----+ - * |      must be zero     | Q3| I3| Q2| I2| Q1| I1| Q0| I0|Z| NCH | - * +-----------------------+-------+-------+-------+-------+-+-----+ - */ -static boost::uint32_t calc_rx_mux( -    const subdev_spec_t &subdev_spec, wax::obj mboard -){ -    //create look-up-table for mapping dboard name and connection type to ADC flags -    static const int ADC0 = 0, ADC1 = 1, ADC2 = 2, ADC3 = 3; -    static const uhd::dict<std::string, uhd::dict<subdev_conn_t, int> > name_to_conn_to_flag = boost::assign::map_list_of -        ("A", boost::assign::map_list_of -            (SUBDEV_CONN_COMPLEX_IQ, calc_rx_mux_pair(ADC0, ADC1)) //I and Q -            (SUBDEV_CONN_COMPLEX_QI, calc_rx_mux_pair(ADC1, ADC0)) //I and Q -            (SUBDEV_CONN_REAL_I,     calc_rx_mux_pair(ADC0, ADC0)) //I and Q (Q identical but ignored Z=1) -            (SUBDEV_CONN_REAL_Q,     calc_rx_mux_pair(ADC1, ADC1)) //I and Q (Q identical but ignored Z=1) -        ) -        ("B", boost::assign::map_list_of -            (SUBDEV_CONN_COMPLEX_IQ, calc_rx_mux_pair(ADC2, ADC3)) //I and Q -            (SUBDEV_CONN_COMPLEX_QI, calc_rx_mux_pair(ADC3, ADC2)) //I and Q -            (SUBDEV_CONN_REAL_I,     calc_rx_mux_pair(ADC2, ADC2)) //I and Q (Q identical but ignored Z=1) -            (SUBDEV_CONN_REAL_Q,     calc_rx_mux_pair(ADC3, ADC3)) //I and Q (Q identical but ignored Z=1) -        ) -    ; - -    //extract the number of channels -    size_t nchan = subdev_spec.size(); - -    //calculate the channel flags -    int channel_flags = 0; -    size_t num_reals = 0, num_quads = 0; -    BOOST_FOREACH(const subdev_spec_pair_t &pair, uhd::reversed(subdev_spec)){ -        wax::obj dboard = mboard[named_prop_t(MBOARD_PROP_RX_DBOARD, pair.db_name)]; -        wax::obj subdev = dboard[named_prop_t(DBOARD_PROP_SUBDEV, pair.sd_name)]; -        subdev_conn_t conn = subdev[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>(); -        switch(conn){ -        case SUBDEV_CONN_COMPLEX_IQ: -        case SUBDEV_CONN_COMPLEX_QI: num_quads++; break; -        case SUBDEV_CONN_REAL_I: -        case SUBDEV_CONN_REAL_Q:     num_reals++; break; -        } -        channel_flags = (channel_flags << 4) | name_to_conn_to_flag[pair.db_name][conn]; -    } - -    //calculate Z: -    //    for all real sources: Z = 1 -    //    for all quadrature sources: Z = 0 -    //    for mixed sources: warning + Z = 0 -    int Z = (num_quads > 0)? 0 : 1; -    if (num_quads != 0 and num_reals != 0) UHD_MSG(warning) << boost::format( -        "Mixing real and quadrature rx subdevices is not supported.\n" -        "The Q input to the real source(s) will be non-zero.\n" -    ); - -    //calculate the rx mux value -    return ((channel_flags & 0xffff) << 4) | ((Z & 0x1) << 3) | ((nchan & 0x7) << 0); -} - -/*********************************************************************** - * Calculate the TX mux value: - *    The I and Q mux values are intentionally reversed to flip I and Q - *    to account for the reversal in the type conversion routines. - **********************************************************************/ -static int calc_tx_mux_pair(int chn_for_i, int chn_for_q){ -    return (chn_for_i << 4) | (chn_for_q << 0); //shift reversal here -} - -/*! - *    3                   2                   1                   0 - *  1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 - * +-----------------------+-------+-------+-------+-------+-+-----+ - * |                       | DAC1Q | DAC1I | DAC0Q | DAC0I |0| NCH | - * +-----------------------------------------------+-------+-+-----+ - */ -static boost::uint32_t calc_tx_mux( -    const subdev_spec_t &subdev_spec, wax::obj mboard -){ -    //create look-up-table for mapping channel number and connection type to flags -    static const int ENB = 1 << 3, CHAN_I0 = 0, CHAN_Q0 = 1, CHAN_I1 = 2, CHAN_Q1 = 3; -    static const uhd::dict<size_t, uhd::dict<subdev_conn_t, int> > chan_to_conn_to_flag = boost::assign::map_list_of -        (0, boost::assign::map_list_of -            (SUBDEV_CONN_COMPLEX_IQ, calc_tx_mux_pair(CHAN_I0 | ENB, CHAN_Q0 | ENB)) -            (SUBDEV_CONN_COMPLEX_QI, calc_tx_mux_pair(CHAN_Q0 | ENB, CHAN_I0 | ENB)) -            (SUBDEV_CONN_REAL_I,     calc_tx_mux_pair(CHAN_I0 | ENB, 0            )) -            (SUBDEV_CONN_REAL_Q,     calc_tx_mux_pair(0,             CHAN_I0 | ENB)) -        ) -        (1, boost::assign::map_list_of -            (SUBDEV_CONN_COMPLEX_IQ, calc_tx_mux_pair(CHAN_I1 | ENB, CHAN_Q1 | ENB)) -            (SUBDEV_CONN_COMPLEX_QI, calc_tx_mux_pair(CHAN_Q1 | ENB, CHAN_I1 | ENB)) -            (SUBDEV_CONN_REAL_I,     calc_tx_mux_pair(CHAN_I1 | ENB, 0            )) -            (SUBDEV_CONN_REAL_Q,     calc_tx_mux_pair(0,             CHAN_I1 | ENB)) -        ) -    ; - -    //extract the number of channels -    size_t nchan = subdev_spec.size(); - -    //calculate the channel flags -    int channel_flags = 0, chan = 0; -    uhd::dict<std::string, int> slot_to_chan_count = boost::assign::map_list_of("A", 0)("B", 0); -    BOOST_FOREACH(const subdev_spec_pair_t &pair, subdev_spec){ -        wax::obj dboard = mboard[named_prop_t(MBOARD_PROP_TX_DBOARD, pair.db_name)]; -        wax::obj subdev = dboard[named_prop_t(DBOARD_PROP_SUBDEV, pair.sd_name)]; -        subdev_conn_t conn = subdev[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>(); - -        //combine the channel flags: shift for slot A vs B -        if (pair.db_name == "A") channel_flags |= chan_to_conn_to_flag[chan][conn] << 0; -        if (pair.db_name == "B") channel_flags |= chan_to_conn_to_flag[chan][conn] << 8; - -        //sanity check, only 1 channel per slot -        slot_to_chan_count[pair.db_name]++; -        if (slot_to_chan_count[pair.db_name] > 1){ -            throw uhd::value_error(str(boost::format( -                "dboard slot %s assigned to multiple channels in subdev spec %s" -            ) % pair.db_name % subdev_spec.to_string())); -        } - -        //increment for the next channel -        chan++; -    } - -    //calculate the tx mux value -    return ((channel_flags & 0xffff) << 4) | ((nchan & 0x7) << 0); -} - -/*! - * Capabilities Register - * - *    3                   2                   1                   0 - *  1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 - * +-----------------------------------------------+-+-----+-+-----+ - * |               Reserved                        |T|DUCs |R|DDCs | - * +-----------------------------------------------+-+-----+-+-----+ - */ -size_t usrp1_impl::get_num_ddcs(void){ -    boost::uint32_t regval = _iface->peek32(FR_RB_CAPS); -    return (regval >> 0) & 0x0007; -} - -size_t usrp1_impl::get_num_ducs(void){ -    boost::uint32_t regval = _iface->peek32(FR_RB_CAPS); -    return (regval >> 4) & 0x0007; -} - -bool usrp1_impl::has_rx_halfband(void){ -    boost::uint32_t regval = _iface->peek32(FR_RB_CAPS); -    return (regval >> 3) & 0x0001; -} - -bool usrp1_impl::has_tx_halfband(void){ -    boost::uint32_t regval = _iface->peek32(FR_RB_CAPS); -    return (regval >> 7) & 0x0001; -} - -/*********************************************************************** - * Mboard Initialization - **********************************************************************/ -void usrp1_impl::mboard_init(void) -{ -    _mboard_proxy = wax_obj_proxy::make( -                     boost::bind(&usrp1_impl::mboard_get, this, _1, _2), -                     boost::bind(&usrp1_impl::mboard_set, this, _1, _2)); - -    // Normal mode with no loopback or Rx counting -    _iface->poke32(FR_MODE, 0x00000000); -    _iface->poke32(FR_DEBUG_EN, 0x00000000); -    _iface->poke32(FR_RX_SAMPLE_RATE_DIV, 0x00000001); //divide by 2 -    _iface->poke32(FR_TX_SAMPLE_RATE_DIV, 0x00000001); //divide by 2 -    _iface->poke32(FR_DC_OFFSET_CL_EN, 0x0000000f); - -    // Reset offset correction registers -    _iface->poke32(FR_ADC_OFFSET_0, 0x00000000); -    _iface->poke32(FR_ADC_OFFSET_1, 0x00000000); -    _iface->poke32(FR_ADC_OFFSET_2, 0x00000000); -    _iface->poke32(FR_ADC_OFFSET_3, 0x00000000); - -    // Set default for RX format to 16-bit I&Q and no half-band filter bypass -    _iface->poke32(FR_RX_FORMAT, 0x00000300); - -    // Set default for TX format to 16-bit I&Q -    _iface->poke32(FR_TX_FORMAT, 0x00000000); - -    UHD_LOG -        << "USRP1 Capabilities" << std::endl -        << "    number of duc's: " << get_num_ddcs() << std::endl -        << "    number of ddc's: " << get_num_ducs() << std::endl -        << "    rx halfband:     " << has_rx_halfband() << std::endl -        << "    tx halfband:     " << has_tx_halfband() << std::endl -    ; -} - -/*********************************************************************** - * Mboard Get - **********************************************************************/ -static prop_names_t dboard_names = boost::assign::list_of("A")("B"); - -void usrp1_impl::mboard_get(const wax::obj &key_, wax::obj &val) -{ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<mboard_prop_t>()){ -    case MBOARD_PROP_NAME: -        val = std::string("usrp1 mboard - " + _iface->mb_eeprom["serial"]); -        return; - -    case MBOARD_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case MBOARD_PROP_RX_DBOARD: -        uhd::assert_has(dboard_names, key.name, "dboard name"); -        if (key.name == "A") val = _rx_dboard_proxies[DBOARD_SLOT_A]->get_link(); -        if (key.name == "B") val = _rx_dboard_proxies[DBOARD_SLOT_B]->get_link(); -        return; - -    case MBOARD_PROP_RX_DBOARD_NAMES: -        val = dboard_names; -        return; - -    case MBOARD_PROP_TX_DBOARD: -        uhd::assert_has(dboard_names, key.name, "dboard name"); -        if (key.name == "A") val = _tx_dboard_proxies[DBOARD_SLOT_A]->get_link(); -        if (key.name == "B") val = _tx_dboard_proxies[DBOARD_SLOT_B]->get_link(); -        return; - -    case MBOARD_PROP_TX_DBOARD_NAMES: -        val = dboard_names; -        return; - -    case MBOARD_PROP_RX_DSP: -        val = _rx_dsp_proxies.get(key.name)->get_link(); -        return; - -    case MBOARD_PROP_RX_DSP_NAMES: -        val = _rx_dsp_proxies.keys(); -        return; - -    case MBOARD_PROP_TX_DSP: -        val = _tx_dsp_proxies.get(key.name)->get_link(); -        return; - -    case MBOARD_PROP_TX_DSP_NAMES: -        val = _tx_dsp_proxies.keys(); -        return; - -    case MBOARD_PROP_CLOCK_CONFIG: -        val = clock_config_t::internal(); -        return; - -    case MBOARD_PROP_RX_SUBDEV_SPEC: -        val = _rx_subdev_spec; -        return; - -    case MBOARD_PROP_TX_SUBDEV_SPEC: -        val = _tx_subdev_spec; -        return; - -    case MBOARD_PROP_EEPROM_MAP: -        val = _iface->mb_eeprom; -        return; - -    case MBOARD_PROP_TIME_NOW: -        val = _soft_time_ctrl->get_time(); -        return; - -    case MBOARD_PROP_CLOCK_RATE: -        val = _clock_ctrl->get_master_clock_freq(); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -/*********************************************************************** - * Mboard Set - **********************************************************************/ -void usrp1_impl::mboard_set(const wax::obj &key, const wax::obj &val) -{ -    if(key.type() == typeid(std::string)) { -      if(key.as<std::string>() == "load_eeprom") { -        std::string usrp1_eeprom_image = val.as<std::string>(); -        UHD_MSG(status) << "USRP1 EEPROM image: " << usrp1_eeprom_image << std::endl; -        _ctrl_transport->usrp_load_eeprom(val.as<std::string>()); -      } -      return; -   	} - -    //handle the get request conditioned on the key -    switch(key.as<mboard_prop_t>()){ - -    case MBOARD_PROP_RX_SUBDEV_SPEC:{ -        _rx_subdev_spec = val.as<subdev_spec_t>(); -        if (_rx_subdev_spec.size() > this->get_num_ddcs()){ -            throw uhd::value_error(str(boost::format( -                "USRP1 suports up to %u RX channels.\n" -                "However, this RX subdev spec requires %u channels\n" -            ) % this->get_num_ddcs() % _rx_subdev_spec.size())); -        } -        verify_rx_subdev_spec(_rx_subdev_spec, _mboard_proxy->get_link()); -        //set the mux and set the number of rx channels -        bool s = this->disable_rx(); -        _iface->poke32(FR_RX_MUX, calc_rx_mux(_rx_subdev_spec, _mboard_proxy->get_link())); -        this->restore_rx(s); -        this->update_xport_channel_mapping(); -    }return; - -    case MBOARD_PROP_TX_SUBDEV_SPEC:{ -        _tx_subdev_spec = val.as<subdev_spec_t>(); -        if (_tx_subdev_spec.size() > this->get_num_ducs()){ -            throw uhd::value_error(str(boost::format( -                "USRP1 suports up to %u TX channels.\n" -                "However, this TX subdev spec requires %u channels\n" -            ) % this->get_num_ducs() % _tx_subdev_spec.size())); -        } -        verify_tx_subdev_spec(_tx_subdev_spec, _mboard_proxy->get_link()); -        //set the mux and set the number of tx channels -        bool s = this->disable_tx(); -        _iface->poke32(FR_TX_MUX, calc_tx_mux(_tx_subdev_spec, _mboard_proxy->get_link())); -        this->restore_tx(s); -        this->update_xport_channel_mapping(); -    }return; - -    case MBOARD_PROP_EEPROM_MAP: -        // Step1: commit the map, writing only those values set. -        // Step2: readback the entire eeprom map into the iface. -        val.as<mboard_eeprom_t>().commit(*_iface, mboard_eeprom_t::MAP_B000); -        _iface->mb_eeprom = mboard_eeprom_t(*_iface, mboard_eeprom_t::MAP_B000); -        return; - -    case MBOARD_PROP_TIME_NOW: -        _soft_time_ctrl->set_time(val.as<time_spec_t>()); -        return; - -    case MBOARD_PROP_CLOCK_RATE: -        UHD_MSG(warning) -            << "I see that you are setting the master clock rate from the API.\n" -            << "You may find it more convenient to burn this setting into the EEPROM.\n" -            << "See the application notes for USRP1 for further instructions.\n" -        ; -        _clock_ctrl->set_master_clock_freq(val.as<double>()); -        this->update_xport_channel_mapping(); -        return; - -    case MBOARD_PROP_CLOCK_CONFIG:{ -        clock_config_t clock_config = val.as<clock_config_t>(); -        if (clock_config.ref_source != clock_config_t::REF_INT){ -            throw uhd::value_error("USRP1 clock config: reference source must be set to internal"); -        } -        if (clock_config.pps_source != clock_config_t::PPS_INT){ -            throw uhd::value_error("USRP1 clock config: PPS source must be set to internal"); -        } -    }return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/usrp1/soft_time_ctrl.cpp b/host/lib/usrp/usrp1/soft_time_ctrl.cpp index 1bab34e7b..ac0899e28 100644 --- a/host/lib/usrp/usrp1/soft_time_ctrl.cpp +++ b/host/lib/usrp/usrp1/soft_time_ctrl.cpp @@ -16,8 +16,7 @@  //  #include "soft_time_ctrl.hpp" -#include <uhd/transport/bounded_buffer.hpp> -#include <boost/any.hpp> +#include <boost/make_shared.hpp>  #include <boost/thread/thread.hpp>  #include <boost/thread/barrier.hpp>  #include <boost/thread/condition_variable.hpp> @@ -41,6 +40,8 @@ public:          _nsamps_remaining(0),          _stream_mode(stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS),          _cmd_queue(2), +        _async_msg_queue(100), +        _inline_msg_queue(100),          _stream_on_off(stream_on_off)      {          //synchronously spawn a new thread @@ -89,32 +90,47 @@ public:      /*******************************************************************       * Receive control       ******************************************************************/ -    void recv_post(rx_metadata_t &md, size_t &nsamps){ +    size_t recv_post(rx_metadata_t &md, const size_t nsamps){          boost::mutex::scoped_lock lock(_update_mutex); +        //Since it timed out on the receive, check for inline messages... +        //Must do a post check because recv() will not wake up for a message. +        if (md.error_code == rx_metadata_t::ERROR_CODE_TIMEOUT){ +            if (_inline_msg_queue.pop_with_haste(md)) return 0; +        } +          //load the metadata with the expected time          md.has_time_spec = true;          md.time_spec = time_now();          //none of the stuff below matters in continuous streaming mode -        if (_stream_mode == stream_cmd_t::STREAM_MODE_START_CONTINUOUS) return; +        if (_stream_mode == stream_cmd_t::STREAM_MODE_START_CONTINUOUS) return nsamps;          //When to stop streaming:          //The samples have been received and the stream mode is non-continuous.          //Rewrite the sample count to clip to the requested number of samples. -        if (_nsamps_remaining <= nsamps){ -            nsamps = _nsamps_remaining; //set nsamps, then stop +        if (_nsamps_remaining <= nsamps) switch(_stream_mode){ +        case stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_MORE:{ +            rx_metadata_t metadata; +            metadata.has_time_spec = true; +            metadata.time_spec = this->time_now(); +            metadata.error_code = rx_metadata_t::ERROR_CODE_BROKEN_CHAIN; +            _inline_msg_queue.push_with_pop_on_full(metadata); +        } //continue to next case... +        case stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_DONE:              md.end_of_burst = true; -            stream_on_off(false); -            return; +            this->issue_stream_cmd(stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS); +            return _nsamps_remaining; +        default: break;          }          //update the consumed samples          _nsamps_remaining -= nsamps; +        return nsamps;      }      void issue_stream_cmd(const stream_cmd_t &cmd){ -        _cmd_queue.push_with_wait(cmd); +        _cmd_queue.push_with_wait(boost::make_shared<stream_cmd_t>(cmd));      }      void stream_on_off(bool enb){ @@ -134,7 +150,12 @@ public:          //handle late packets          if (time_at < time_now()){ -            //TODO post async message +            async_metadata_t metadata; +            metadata.channel = 0; +            metadata.has_time_spec = true; +            metadata.time_spec = this->time_now(); +            metadata.event_code = async_metadata_t::EVENT_CODE_TIME_ERROR; +            _async_msg_queue.push_with_pop_on_full(metadata);              return true;          } @@ -153,7 +174,13 @@ public:          if (not cmd.stream_now){              time_spec_t time_at(cmd.time_spec - TWIDDLE);              if (time_at < time_now()){ -                //TODO inject late cmd inline error +                rx_metadata_t metadata; +                metadata.has_time_spec = true; +                metadata.time_spec = this->time_now(); +                metadata.error_code = rx_metadata_t::ERROR_CODE_LATE_COMMAND; +                _inline_msg_queue.push_with_pop_on_full(metadata); +                this->issue_stream_cmd(stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS); +                return;              }              else{                  sleep_until_time(lock, time_at); @@ -180,20 +207,30 @@ public:      void recv_cmd_dispatcher(boost::barrier &spawn_barrier){          spawn_barrier.wait();          try{ -            boost::any cmd; +            boost::shared_ptr<stream_cmd_t> cmd;              while (true){                  _cmd_queue.pop_with_wait(cmd); -                recv_cmd_handle_cmd(boost::any_cast<stream_cmd_t>(cmd)); +                recv_cmd_handle_cmd(*cmd);              }          } catch(const boost::thread_interrupted &){}      } +    bounded_buffer<async_metadata_t> &get_async_queue(void){ +        return _async_msg_queue; +    } + +    bounded_buffer<rx_metadata_t> &get_inline_queue(void){ +        return _inline_msg_queue; +    } +  private:      boost::mutex _update_mutex;      size_t _nsamps_remaining;      stream_cmd_t::stream_mode_t _stream_mode;      time_spec_t _time_offset; -    bounded_buffer<boost::any> _cmd_queue; +    bounded_buffer<boost::shared_ptr<stream_cmd_t> > _cmd_queue; +    bounded_buffer<async_metadata_t> _async_msg_queue; +    bounded_buffer<rx_metadata_t> _inline_msg_queue;      const cb_fcn_type _stream_on_off;      boost::thread_group _thread_group;  }; diff --git a/host/lib/usrp/usrp1/soft_time_ctrl.hpp b/host/lib/usrp/usrp1/soft_time_ctrl.hpp index 7fdac7fc8..e91aaf6a2 100644 --- a/host/lib/usrp/usrp1/soft_time_ctrl.hpp +++ b/host/lib/usrp/usrp1/soft_time_ctrl.hpp @@ -21,6 +21,7 @@  #include <uhd/types/stream_cmd.hpp>  #include <uhd/types/time_spec.hpp>  #include <uhd/types/metadata.hpp> +#include <uhd/transport/bounded_buffer.hpp>  #include <boost/utility.hpp>  #include <boost/shared_ptr.hpp>  #include <boost/function.hpp> @@ -45,8 +46,6 @@ public:       * \return a new soft time control object       */      static sptr make(const cb_fcn_type &stream_on_off); -        //TODO pass in the error queue for async msgs -        //TODO pass in the queue for inline msgs      //! Set the current time      virtual void set_time(const time_spec_t &time) = 0; @@ -55,13 +54,19 @@ public:      virtual time_spec_t get_time(void) = 0;      //! Call after the internal recv function -    virtual void recv_post(rx_metadata_t &md, size_t &nsamps) = 0; +    virtual size_t recv_post(rx_metadata_t &md, const size_t nsamps) = 0;      //! Call before the internal send function      virtual bool send_pre(const tx_metadata_t &md, double &timeout) = 0;      //! Issue a stream command to receive      virtual void issue_stream_cmd(const stream_cmd_t &cmd) = 0; + +    //! Get access to a buffer of async metadata +    virtual transport::bounded_buffer<async_metadata_t> &get_async_queue(void) = 0; + +    //! Get access to a buffer of inline metadata +    virtual transport::bounded_buffer<rx_metadata_t> &get_inline_queue(void) = 0;  };  }} //namespace diff --git a/host/lib/usrp/usrp1/usrp1_calc_mux.hpp b/host/lib/usrp/usrp1/usrp1_calc_mux.hpp new file mode 100644 index 000000000..31c190db0 --- /dev/null +++ b/host/lib/usrp/usrp1/usrp1_calc_mux.hpp @@ -0,0 +1,156 @@ +// +// Copyright 2010-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 <uhd/config.hpp> +#include <uhd/exception.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/utils/algorithm.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <utility> +#include <vector> +#include <string> + +#ifndef INCLUDED_USRP1_CALC_MUX_HPP +#define INCLUDED_USRP1_CALC_MUX_HPP + +//db_name, conn_type for the mux calculations below... +typedef std::pair<std::string, std::string> mapping_pair_t; + +/*********************************************************************** + * Calculate the RX mux value: + *    The I and Q mux values are intentionally reversed to flip I and Q + *    to account for the reversal in the type conversion routines. + **********************************************************************/ +static int calc_rx_mux_pair(int adc_for_i, int adc_for_q){ +    return (adc_for_i << 2) | (adc_for_q << 0); //shift reversal here +} + +/*! + *    3                   2                   1                   0 + *  1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 + * +-----------------------+-------+-------+-------+-------+-+-----+ + * |      must be zero     | Q3| I3| Q2| I2| Q1| I1| Q0| I0|Z| NCH | + * +-----------------------+-------+-------+-------+-------+-+-----+ + */ +static boost::uint32_t calc_rx_mux(const std::vector<mapping_pair_t> &mapping){ +    //create look-up-table for mapping dboard name and connection type to ADC flags +    static const int ADC0 = 0, ADC1 = 1, ADC2 = 2, ADC3 = 3; +    static const uhd::dict<std::string, uhd::dict<std::string, int> > name_to_conn_to_flag = boost::assign::map_list_of +        ("A", boost::assign::map_list_of +            ("IQ", calc_rx_mux_pair(ADC0, ADC1)) //I and Q +            ("QI", calc_rx_mux_pair(ADC1, ADC0)) //I and Q +            ("I",  calc_rx_mux_pair(ADC0, ADC0)) //I and Q (Q identical but ignored Z=1) +            ("Q",  calc_rx_mux_pair(ADC1, ADC1)) //I and Q (Q identical but ignored Z=1) +        ) +        ("B", boost::assign::map_list_of +            ("IQ", calc_rx_mux_pair(ADC2, ADC3)) //I and Q +            ("QI", calc_rx_mux_pair(ADC3, ADC2)) //I and Q +            ("I",  calc_rx_mux_pair(ADC2, ADC2)) //I and Q (Q identical but ignored Z=1) +            ("Q",  calc_rx_mux_pair(ADC3, ADC3)) //I and Q (Q identical but ignored Z=1) +        ) +    ; + +    //extract the number of channels +    const size_t nchan = mapping.size(); + +    //calculate the channel flags +    int channel_flags = 0; +    size_t num_reals = 0, num_quads = 0; +    BOOST_FOREACH(const mapping_pair_t &pair, uhd::reversed(mapping)){ +        const std::string name = pair.first, conn = pair.second; +        if (conn == "IQ" or conn == "QI") num_quads++; +        if (conn == "I" or conn == "Q") num_reals++; +        channel_flags = (channel_flags << 4) | name_to_conn_to_flag[name][conn]; +    } + +    //calculate Z: +    //    for all real sources: Z = 1 +    //    for all quadrature sources: Z = 0 +    //    for mixed sources: warning + Z = 0 +    int Z = (num_quads > 0)? 0 : 1; +    if (num_quads != 0 and num_reals != 0) UHD_MSG(warning) << boost::format( +        "Mixing real and quadrature rx subdevices is not supported.\n" +        "The Q input to the real source(s) will be non-zero.\n" +    ); + +    //calculate the rx mux value +    return ((channel_flags & 0xffff) << 4) | ((Z & 0x1) << 3) | ((nchan & 0x7) << 0); +} + +/*********************************************************************** + * Calculate the TX mux value: + *    The I and Q mux values are intentionally reversed to flip I and Q + *    to account for the reversal in the type conversion routines. + **********************************************************************/ +static int calc_tx_mux_pair(int chn_for_i, int chn_for_q){ +    return (chn_for_i << 4) | (chn_for_q << 0); //shift reversal here +} + +/*! + *    3                   2                   1                   0 + *  1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 + * +-----------------------+-------+-------+-------+-------+-+-----+ + * |                       | DAC1Q | DAC1I | DAC0Q | DAC0I |0| NCH | + * +-----------------------------------------------+-------+-+-----+ + */ +static boost::uint32_t calc_tx_mux(const std::vector<mapping_pair_t> &mapping){ +    //create look-up-table for mapping channel number and connection type to flags +    static const int ENB = 1 << 3, CHAN_I0 = 0, CHAN_Q0 = 1, CHAN_I1 = 2, CHAN_Q1 = 3; +    static const uhd::dict<size_t, uhd::dict<std::string, int> > chan_to_conn_to_flag = boost::assign::map_list_of +        (0, boost::assign::map_list_of +            ("IQ", calc_tx_mux_pair(CHAN_I0 | ENB, CHAN_Q0 | ENB)) +            ("QI", calc_tx_mux_pair(CHAN_Q0 | ENB, CHAN_I0 | ENB)) +            ("I",  calc_tx_mux_pair(CHAN_I0 | ENB, 0            )) +            ("Q",  calc_tx_mux_pair(0,             CHAN_I0 | ENB)) +        ) +        (1, boost::assign::map_list_of +            ("IQ", calc_tx_mux_pair(CHAN_I1 | ENB, CHAN_Q1 | ENB)) +            ("QI", calc_tx_mux_pair(CHAN_Q1 | ENB, CHAN_I1 | ENB)) +            ("I",  calc_tx_mux_pair(CHAN_I1 | ENB, 0            )) +            ("Q",  calc_tx_mux_pair(0,             CHAN_I1 | ENB)) +        ) +    ; + +    //extract the number of channels +    size_t nchan = mapping.size(); + +    //calculate the channel flags +    int channel_flags = 0, chan = 0; +    uhd::dict<std::string, int> slot_to_chan_count = boost::assign::map_list_of("A", 0)("B", 0); +    BOOST_FOREACH(const mapping_pair_t &pair, mapping){ +        const std::string name = pair.first, conn = pair.second; + +        //combine the channel flags: shift for slot A vs B +        if (name == "A") channel_flags |= chan_to_conn_to_flag[chan][conn] << 0; +        if (name == "B") channel_flags |= chan_to_conn_to_flag[chan][conn] << 8; + +        //sanity check, only 1 channel per slot +        slot_to_chan_count[name]++; +        if (slot_to_chan_count[name] > 1) throw uhd::value_error( +            "cannot assign dboard slot to multiple channels: " + name +        ); + +        //increment for the next channel +        chan++; +    } + +    //calculate the tx mux value +    return ((channel_flags & 0xffff) << 4) | ((nchan & 0x7) << 0); +} + +#endif /* INCLUDED_USRP1_CALC_MUX_HPP */ diff --git a/host/lib/usrp/usrp1/usrp1_iface.cpp b/host/lib/usrp/usrp1/usrp1_iface.cpp index 8877f19db..c790aecb4 100644 --- a/host/lib/usrp/usrp1/usrp1_iface.cpp +++ b/host/lib/usrp/usrp1/usrp1_iface.cpp @@ -36,7 +36,6 @@ public:      usrp1_iface_impl(uhd::usrp::fx2_ctrl::sptr ctrl_transport)      {          _ctrl_transport = ctrl_transport; -        mb_eeprom = mboard_eeprom_t(*this, mboard_eeprom_t::MAP_B000);      }      ~usrp1_iface_impl(void) @@ -102,78 +101,16 @@ public:          throw uhd::not_implemented_error("Unhandled command peek16()");          return 0;      } -     -    void write_uart(boost::uint8_t, const std::string &) { -        throw uhd::not_implemented_error("Unhandled command write_uart()"); -    } -     -    std::string read_uart(boost::uint8_t) { -        throw uhd::not_implemented_error("Unhandled command read_uart()"); -    }      /*******************************************************************       * I2C       ******************************************************************/ -    static const size_t max_i2c_data_bytes = 64; - -    //TODO: make this handle EEPROM page sizes. right now you can't write over a 16-byte boundary. -    //to accomplish this you'll have to have addr offset as a separate parameter. - -    void write_i2c(boost::uint8_t addr, const byte_vector_t &bytes) -    { -        UHD_LOGV(always) << "write_i2c:" << std::endl -            << "  addr 0x" << std::hex << int(addr) << std::endl -            << "  len " << bytes.size() << std::endl -        ; -        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 = _ctrl_transport->usrp_i2c_write(addr & 0xff, -                                             buff, -                                             bytes.size()); - -        // TODO throw and catch i2c failures during eeprom read -        if (ret < 0) -            UHD_LOGV(often) << "USRP: failed i2c write: " << ret << std::endl; +    void write_i2c(boost::uint8_t addr, const byte_vector_t &bytes){ +        return _ctrl_transport->write_i2c(addr, bytes);      } -    byte_vector_t read_i2c(boost::uint8_t addr, size_t num_bytes) -    { -        UHD_LOGV(always) << "read_i2c:" << std::endl -            << "  addr 0x" << std::hex << int(addr) << std::endl -            << "  len " << num_bytes << std::endl -        ; -        UHD_ASSERT_THROW(num_bytes < max_i2c_data_bytes); - -        unsigned char buff[max_i2c_data_bytes]; -        int ret = _ctrl_transport->usrp_i2c_read(addr & 0xff, -                                            buff, -                                            num_bytes); - -        // TODO throw and catch i2c failures during eeprom read -        if (ret < 0 or (unsigned)ret < num_bytes) { -            UHD_LOGV(often) << "USRP: failed i2c read: " << ret << std::endl; -            return byte_vector_t(num_bytes, 0xff);  -        } - -        byte_vector_t out_bytes; -        for (size_t i = 0; i < num_bytes; i++) -            out_bytes.push_back(buff[i]); - -        return out_bytes;  -    } - -    //! overload read_eeprom to handle multi-byte reads -    byte_vector_t read_eeprom( -        boost::uint8_t addr, -        boost::uint8_t offset, -        size_t num_bytes -    ){ -        //do a zero byte write to start read cycle -        this->write_i2c(addr, byte_vector_t(1, offset)); -        return this->read_i2c(addr, num_bytes); //read all bytes +    byte_vector_t read_i2c(boost::uint8_t addr, size_t num_bytes){ +        return _ctrl_transport->read_i2c(addr, num_bytes);      }      /******************************************************************* @@ -255,37 +192,6 @@ public:          }      } -    /******************************************************************* -     * Firmware  -     * -     * This call is deprecated. -     ******************************************************************/ -    void write_firmware_cmd(boost::uint8_t request, -                            boost::uint16_t value, -                            boost::uint16_t index, -                            unsigned char *buff, -                            boost::uint16_t length) -    { -        int ret; - -        if (request & 0x80) { -            ret = _ctrl_transport->usrp_control_read(request, -                                                     value, -                                                     index, -                                                     buff, -                                                     length); -        } -        else { -            ret = _ctrl_transport->usrp_control_write(request, -                                                      value, -                                                      index, -                                                      buff, -                                                      length); -        } - -        if (ret < 0) throw uhd::io_error("USRP1: failed firmware command"); -    } -  private:      uhd::usrp::fx2_ctrl::sptr _ctrl_transport;  }; diff --git a/host/lib/usrp/usrp1/usrp1_iface.hpp b/host/lib/usrp/usrp1/usrp1_iface.hpp index e480c22ea..c1ac34f25 100644 --- a/host/lib/usrp/usrp1/usrp1_iface.hpp +++ b/host/lib/usrp/usrp1/usrp1_iface.hpp @@ -18,43 +18,27 @@  #ifndef INCLUDED_USRP1_IFACE_HPP  #define INCLUDED_USRP1_IFACE_HPP -#include <uhd/usrp/mboard_iface.hpp> +#include "fx2_ctrl.hpp" +#include "wb_iface.hpp" +#include <uhd/types/serial.hpp>  #include <boost/shared_ptr.hpp>  #include <boost/utility.hpp> -#include "../fx2/fx2_ctrl.hpp"  /*!   * The usrp1 interface class:   * Provides a set of functions to implementation layer.   * Including spi, peek, poke, control...   */ -class usrp1_iface : public uhd::usrp::mboard_iface, boost::noncopyable{ +class usrp1_iface : public wb_iface, public uhd::i2c_iface, public uhd::spi_iface, boost::noncopyable{  public:      typedef boost::shared_ptr<usrp1_iface> sptr; -    //motherboard eeprom map structure -    uhd::usrp::mboard_eeprom_t mb_eeprom; -      /*!       * Make a new usrp1 interface with the control transport.       * \param ctrl_transport the usrp controller object       * \return a new usrp1 interface object       */      static sptr make(uhd::usrp::fx2_ctrl::sptr ctrl_transport); - -    /*! -     * Perform a general USB firmware OUT operation -     * \param request  -     * \param value -     * \param index  -     * \param data  -     * \return  -     */ -    virtual void write_firmware_cmd(boost::uint8_t request, -                                   boost::uint16_t value, -                                   boost::uint16_t index, -                                   unsigned char* buff, -                                   boost::uint16_t length) = 0;  };  #endif /* INCLUDED_USRP1_IFACE_HPP */ diff --git a/host/lib/usrp/usrp1/usrp1_impl.cpp b/host/lib/usrp/usrp1/usrp1_impl.cpp index a3d502038..78137178b 100644 --- a/host/lib/usrp/usrp1/usrp1_impl.cpp +++ b/host/lib/usrp/usrp1/usrp1_impl.cpp @@ -16,13 +16,14 @@  //  #include "usrp1_impl.hpp" -#include "fpga_regs_standard.h"  #include "usrp_spi_defs.h" +#include "usrp_commands.h" +#include "fpga_regs_standard.h" +#include "fpga_regs_common.h" +#include "usrp_i2c_addr.h"  #include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp>  #include <uhd/transport/usb_control.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> @@ -101,10 +102,11 @@ static device_addrs_t usrp1_find(const device_addr_t &hint)          try{control = usb_control::make(handle);}          catch(const uhd::exception &){continue;} //ignore claimed -        usrp1_iface::sptr iface = usrp1_iface::make(fx2_ctrl::make(control)); +        fx2_ctrl::sptr fx2_ctrl = fx2_ctrl::make(control); +        const mboard_eeprom_t mb_eeprom(*fx2_ctrl, mboard_eeprom_t::MAP_B000);          device_addr_t new_addr;          new_addr["type"] = "usrp1"; -        new_addr["name"] = iface->mb_eeprom["name"]; +        new_addr["name"] = mb_eeprom["name"];          new_addr["serial"] = handle->get_serial();          //this is a found usrp1 when the hint serial and name match or blank          if ( @@ -122,6 +124,17 @@ static device_addrs_t usrp1_find(const device_addr_t &hint)   * Make   **********************************************************************/  static device::sptr usrp1_make(const device_addr_t &device_addr){ +    return device::sptr(new usrp1_impl(device_addr)); +} + +UHD_STATIC_BLOCK(register_usrp1_device){ +    device::register_device(&usrp1_find, &usrp1_make); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +usrp1_impl::usrp1_impl(const device_addr_t &device_addr){      UHD_MSG(status) << "Opening a USRP1 device..." << std::endl;      //extract the FPGA path for the USRP1 @@ -144,67 +157,232 @@ static device::sptr usrp1_make(const device_addr_t &device_addr){      }      UHD_ASSERT_THROW(handle.get() != NULL); //better be found -    //create control objects and a data transport -    usb_control::sptr ctrl_transport = usb_control::make(handle); -    fx2_ctrl::sptr usrp_ctrl = fx2_ctrl::make(ctrl_transport); -    usrp_ctrl->usrp_load_fpga(usrp1_fpga_image); -    usrp_ctrl->usrp_init(); -    usb_zero_copy::sptr data_transport = usb_zero_copy::make( +    //////////////////////////////////////////////////////////////////// +    // Create controller objects +    //////////////////////////////////////////////////////////////////// +    //usb_control::sptr usb_ctrl = usb_control::make(handle); +    _fx2_ctrl = fx2_ctrl::make(usb_control::make(handle)); +    _fx2_ctrl->usrp_load_fpga(usrp1_fpga_image); +    _fx2_ctrl->usrp_init(); +    _data_transport = usb_zero_copy::make(          handle,        // identifier          6,             // IN endpoint          2,             // OUT endpoint          device_addr    // param hints      ); - -    //create the usrp1 implementation guts -    return device::sptr(new usrp1_impl(data_transport, usrp_ctrl)); -} - -UHD_STATIC_BLOCK(register_usrp1_device){ -    device::register_device(&usrp1_find, &usrp1_make); -} - -/*********************************************************************** - * Structors - **********************************************************************/ -usrp1_impl::usrp1_impl(uhd::transport::usb_zero_copy::sptr data_transport, -                       uhd::usrp::fx2_ctrl::sptr ctrl_transport) - : _data_transport(data_transport), _ctrl_transport(ctrl_transport) -{ -    _iface = usrp1_iface::make(ctrl_transport); - -    //create clock interface -    _clock_ctrl = usrp1_clock_ctrl::make(_iface); - -    //create codec interface -    _codec_ctrls[DBOARD_SLOT_A] = usrp1_codec_ctrl::make( -        _iface, _clock_ctrl, SPI_ENABLE_CODEC_A -    ); -    _codec_ctrls[DBOARD_SLOT_B] = usrp1_codec_ctrl::make( -        _iface, _clock_ctrl, SPI_ENABLE_CODEC_B +    _iface = usrp1_iface::make(_fx2_ctrl); +    _soft_time_ctrl = soft_time_ctrl::make( +        boost::bind(&usrp1_impl::rx_stream_on_off, this, _1)      ); +    _dbc["A"]; _dbc["B"]; //ensure that keys exist + +    // Normal mode with no loopback or Rx counting +    _iface->poke32(FR_MODE, 0x00000000); +    _iface->poke32(FR_DEBUG_EN, 0x00000000); +    _iface->poke32(FR_RX_SAMPLE_RATE_DIV, 0x00000001); //divide by 2 +    _iface->poke32(FR_TX_SAMPLE_RATE_DIV, 0x00000001); //divide by 2 +    _iface->poke32(FR_DC_OFFSET_CL_EN, 0x0000000f); + +    // Reset offset correction registers +    _iface->poke32(FR_ADC_OFFSET_0, 0x00000000); +    _iface->poke32(FR_ADC_OFFSET_1, 0x00000000); +    _iface->poke32(FR_ADC_OFFSET_2, 0x00000000); +    _iface->poke32(FR_ADC_OFFSET_3, 0x00000000); + +    // Set default for RX format to 16-bit I&Q and no half-band filter bypass +    _iface->poke32(FR_RX_FORMAT, 0x00000300); + +    // Set default for TX format to 16-bit I&Q +    _iface->poke32(FR_TX_FORMAT, 0x00000000); + +    UHD_LOG +        << "USRP1 Capabilities" << std::endl +        << "    number of duc's: " << get_num_ddcs() << std::endl +        << "    number of ddc's: " << get_num_ducs() << std::endl +        << "    rx halfband:     " << has_rx_halfband() << std::endl +        << "    tx halfband:     " << has_tx_halfband() << std::endl +    ; + +    //////////////////////////////////////////////////////////////////// +    // Initialize the properties tree +    //////////////////////////////////////////////////////////////////// +    _tree = property_tree::make(); +    _tree->create<std::string>("/name").set("USRP1 Device"); +    const property_tree::path_type mb_path = "/mboards/0"; +    _tree->create<std::string>(mb_path / "name").set("USRP1 (Classic)"); +    _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_B000); +    _tree->create<mboard_eeprom_t>(mb_path / "eeprom") +        .set(mb_eeprom) +        .subscribe(boost::bind(&usrp1_impl::set_mb_eeprom, this, _1)); + +    //////////////////////////////////////////////////////////////////// +    // create clock control objects +    //////////////////////////////////////////////////////////////////// +    _master_clock_rate = 64e6; +    try{ +        if (not mb_eeprom["mcr"].empty()) +            _master_clock_rate = boost::lexical_cast<double>(mb_eeprom["mcr"]); +    }catch(const std::exception &e){ +        UHD_MSG(error) << "Error parsing FPGA clock rate from EEPROM: " << e.what() << std::endl; +    } +    UHD_MSG(status) << boost::format("Using FPGA clock rate of %fMHz...") % (_master_clock_rate/1e6) << std::endl; +    _tree->create<double>(mb_path / "tick_rate").set(_master_clock_rate); + +    //////////////////////////////////////////////////////////////////// +    // create codec control objects +    //////////////////////////////////////////////////////////////////// +    BOOST_FOREACH(const std::string &db, _dbc.keys()){ +        _dbc[db].codec = usrp1_codec_ctrl::make(_iface, (db == "A")? SPI_ENABLE_CODEC_A : SPI_ENABLE_CODEC_B); +        const property_tree::path_type rx_codec_path = mb_path / "rx_codecs" / db; +        const property_tree::path_type tx_codec_path = mb_path / "tx_codecs" / db; +        _tree->create<std::string>(rx_codec_path / "name").set("ad9522"); +        _tree->create<meta_range_t>(rx_codec_path / "gains/pga/range").set(usrp1_codec_ctrl::rx_pga_gain_range); +        _tree->create<double>(rx_codec_path / "gains/pga/value") +            .coerce(boost::bind(&usrp1_impl::update_rx_codec_gain, this, db, _1)); +        _tree->create<std::string>(tx_codec_path / "name").set("ad9522"); +        _tree->create<meta_range_t>(tx_codec_path / "gains/pga/range").set(usrp1_codec_ctrl::tx_pga_gain_range); +        _tree->create<double>(tx_codec_path / "gains/pga/value") +            .subscribe(boost::bind(&usrp1_codec_ctrl::set_tx_pga_gain, _dbc[db].codec, _1)) +            .publish(boost::bind(&usrp1_codec_ctrl::get_tx_pga_gain, _dbc[db].codec)); +    } -    //initialize the codecs -    codec_init(); +    //////////////////////////////////////////////////////////////////// +    // 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 +    //////////////////////////////////////////////////////////////////// +    _tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec") +        .subscribe(boost::bind(&usrp1_impl::update_rx_subdev_spec, this, _1)); +    _tree->create<subdev_spec_t>(mb_path / "tx_subdev_spec") +        .subscribe(boost::bind(&usrp1_impl::update_tx_subdev_spec, this, _1)); + +    //////////////////////////////////////////////////////////////////// +    // create rx dsp control objects +    //////////////////////////////////////////////////////////////////// +    for (size_t dspno = 0; dspno < get_num_ddcs(); dspno++){ +        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(&usrp1_impl::update_rx_samp_rate, this, _1)); +        _tree->create<double>(rx_dsp_path / "freq/value") +            .coerce(boost::bind(&usrp1_impl::update_rx_dsp_freq, this, dspno, _1)); +        _tree->create<meta_range_t>(rx_dsp_path / "freq/range") +            .set(meta_range_t(-_master_clock_rate/2, +_master_clock_rate/2)); +        _tree->create<stream_cmd_t>(rx_dsp_path / "stream_cmd"); +        if (dspno == 0){ +            //only subscribe the callback for dspno 0 since it will stream all dsps +            _tree->access<stream_cmd_t>(rx_dsp_path / "stream_cmd") +                .subscribe(boost::bind(&soft_time_ctrl::issue_stream_cmd, _soft_time_ctrl, _1)); +        } +    } -    //initialize the mboard -    mboard_init(); +    //////////////////////////////////////////////////////////////////// +    // create tx dsp control objects +    //////////////////////////////////////////////////////////////////// +    for (size_t dspno = 0; dspno < get_num_ducs(); dspno++){ +        property_tree::path_type tx_dsp_path = mb_path / str(boost::format("tx_dsps/%u") % dspno); +        _tree->create<double>(tx_dsp_path / "rate/value") +            .coerce(boost::bind(&usrp1_impl::update_tx_samp_rate, this, _1)); +        _tree->create<double>(tx_dsp_path / "freq/value") +            .coerce(boost::bind(&usrp1_impl::update_tx_dsp_freq, this, dspno, _1)); +        _tree->create<meta_range_t>(tx_dsp_path / "freq/range") //magic scalar comes from codec control: +            .set(meta_range_t(-_master_clock_rate*0.6875, +_master_clock_rate*0.6875)); +    } -    //initialize the dboards -    dboard_init(); +    //////////////////////////////////////////////////////////////////// +    // create time control objects +    //////////////////////////////////////////////////////////////////// +    _tree->create<time_spec_t>(mb_path / "time/now") +        .publish(boost::bind(&soft_time_ctrl::get_time, _soft_time_ctrl)) +        .subscribe(boost::bind(&soft_time_ctrl::set_time, _soft_time_ctrl, _1)); + +    _tree->create<std::vector<std::string> >(mb_path / "clock_source/options").set(std::vector<std::string>(1, "internal")); +    _tree->create<std::vector<std::string> >(mb_path / "time_source/options").set(std::vector<std::string>(1, "none")); +    _tree->create<std::string>(mb_path / "clock_source/value").set("internal"); +    _tree->create<std::string>(mb_path / "time_source/value").set("none"); + +    //////////////////////////////////////////////////////////////////// +    // create dboard control objects +    //////////////////////////////////////////////////////////////////// +    BOOST_FOREACH(const std::string &db, _dbc.keys()){ + +        //read the dboard eeprom to extract the dboard ids +        dboard_eeprom_t rx_db_eeprom, tx_db_eeprom, gdb_eeprom; +        rx_db_eeprom.load(*_fx2_ctrl, (db == "A")? (I2C_ADDR_RX_A) : (I2C_ADDR_RX_B)); +        tx_db_eeprom.load(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A) : (I2C_ADDR_TX_B)); +        gdb_eeprom.load(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A ^ 5) : (I2C_ADDR_TX_B ^ 5)); + +        //create the properties and register subscribers +        _tree->create<dboard_eeprom_t>(mb_path / "dboards" / db/ "rx_eeprom") +            .set(rx_db_eeprom) +            .subscribe(boost::bind(&usrp1_impl::set_db_eeprom, this, db, "rx", _1)); +        _tree->create<dboard_eeprom_t>(mb_path / "dboards" / db/ "tx_eeprom") +            .set(tx_db_eeprom) +            .subscribe(boost::bind(&usrp1_impl::set_db_eeprom, this, db, "tx", _1)); +        _tree->create<dboard_eeprom_t>(mb_path / "dboards" / db/ "gdb_eeprom") +            .set(gdb_eeprom) +            .subscribe(boost::bind(&usrp1_impl::set_db_eeprom, this, db, "gdb", _1)); + +        //create a new dboard interface and manager +        _dbc[db].dboard_iface = make_dboard_iface( +            _iface, _dbc[db].codec, +            (db == "A")? DBOARD_SLOT_A : DBOARD_SLOT_B, +            _master_clock_rate, rx_db_eeprom.id +        ); +        _tree->create<dboard_iface::sptr>(mb_path / "dboards" / db/ "iface").set(_dbc[db].dboard_iface); +        _dbc[db].dboard_manager = dboard_manager::make( +            rx_db_eeprom.id, +            ((gdb_eeprom.id == dboard_id_t::none())? tx_db_eeprom : gdb_eeprom).id, +            _dbc[db].dboard_iface +        ); +        BOOST_FOREACH(const std::string &name, _dbc[db].dboard_manager->get_rx_subdev_names()){ +            dboard_manager::populate_prop_tree_from_subdev( +                _tree, mb_path / "dboards" / db/ "rx_frontends" / name, +                _dbc[db].dboard_manager->get_rx_subdev(name) +            ); +        } +        BOOST_FOREACH(const std::string &name, _dbc[db].dboard_manager->get_tx_subdev_names()){ +            dboard_manager::populate_prop_tree_from_subdev( +                _tree, mb_path / "dboards" / db/ "tx_frontends" / name, +                _dbc[db].dboard_manager->get_tx_subdev(name) +            ); +        } -    //initialize the dsps -    rx_dsp_init(); +        //init the subdev specs if we have a dboard (wont leave this loop empty) +        if (rx_db_eeprom.id != dboard_id_t::none() or _rx_subdev_spec.empty()){ +            _rx_subdev_spec = subdev_spec_t(db + ":" + _dbc[db].dboard_manager->get_rx_subdev_names()[0]); +        } +        if (tx_db_eeprom.id != dboard_id_t::none() or _tx_subdev_spec.empty()){ +            _tx_subdev_spec = subdev_spec_t(db + ":" + _dbc[db].dboard_manager->get_tx_subdev_names()[0]); +        } +    } -    //initialize the dsps -    tx_dsp_init(); +    //initialize io handling +    this->io_init(); -    //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()); +    //////////////////////////////////////////////////////////////////// +    // do some post-init tasks +    //////////////////////////////////////////////////////////////////// +    //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 send/recv -    io_init(); +    _tree->access<subdev_spec_t>(mb_path / "rx_subdev_spec").set(_rx_subdev_spec); +    _tree->access<subdev_spec_t>(mb_path / "tx_subdev_spec").set(_tx_subdev_spec); +   }  usrp1_impl::~usrp1_impl(void){UHD_SAFE_CALL( @@ -212,42 +390,52 @@ usrp1_impl::~usrp1_impl(void){UHD_SAFE_CALL(      this->enable_tx(false);  )} -bool usrp1_impl::recv_async_msg(uhd::async_metadata_t &, double timeout){ -    //dummy fill-in for the recv_async_msg -    boost::this_thread::sleep(boost::posix_time::microseconds(long(timeout*1e6))); -    return false; +/*! + * Capabilities Register + * + *    3                   2                   1                   0 + *  1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 + * +-----------------------------------------------+-+-----+-+-----+ + * |               Reserved                        |T|DUCs |R|DDCs | + * +-----------------------------------------------+-+-----+-+-----+ + */ +size_t usrp1_impl::get_num_ddcs(void){ +    boost::uint32_t regval = _iface->peek32(FR_RB_CAPS); +    return (regval >> 0) & 0x0007;  } -/*********************************************************************** - * Device Get - **********************************************************************/ -void usrp1_impl::get(const wax::obj &key_, wax::obj &val) -{ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<device_prop_t>()){ -    case DEVICE_PROP_NAME: -        val = std::string("usrp1 device"); -        return; - -    case DEVICE_PROP_MBOARD: -        UHD_ASSERT_THROW(key.name == ""); -        val = _mboard_proxy->get_link(); -        return; +size_t usrp1_impl::get_num_ducs(void){ +    boost::uint32_t regval = _iface->peek32(FR_RB_CAPS); +    return (regval >> 4) & 0x0007; +} -    case DEVICE_PROP_MBOARD_NAMES: -        val = prop_names_t(1, ""); //vector of size 1 with empty string -        return; +bool usrp1_impl::has_rx_halfband(void){ +    boost::uint32_t regval = _iface->peek32(FR_RB_CAPS); +    return (regval >> 3) & 0x0001; +} -    default: UHD_THROW_PROP_GET_ERROR(); -    } +bool usrp1_impl::has_tx_halfband(void){ +    boost::uint32_t regval = _iface->peek32(FR_RB_CAPS); +    return (regval >> 7) & 0x0001;  }  /*********************************************************************** - * Device Set + * Properties callback methods below   **********************************************************************/ -void usrp1_impl::set(const wax::obj &, const wax::obj &) -{ -    UHD_THROW_PROP_SET_ERROR(); +void usrp1_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){ +    mb_eeprom.commit(*_fx2_ctrl, mboard_eeprom_t::MAP_B000); +} + +void usrp1_impl::set_db_eeprom(const std::string &db, const std::string &type, const uhd::usrp::dboard_eeprom_t &db_eeprom){ +    if (type == "rx") db_eeprom.store(*_fx2_ctrl, (db == "A")? (I2C_ADDR_RX_A) : (I2C_ADDR_RX_B)); +    if (type == "tx") db_eeprom.store(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A) : (I2C_ADDR_TX_B)); +    if (type == "gdb") db_eeprom.store(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A ^ 5) : (I2C_ADDR_TX_B ^ 5)); +} + +double usrp1_impl::update_rx_codec_gain(const std::string &db, const double gain){ +    //set gain on both I and Q, readback on one +    //TODO in the future, gains should have individual control +    _dbc[db].codec->set_rx_pga_gain(gain, 'A'); +    _dbc[db].codec->set_rx_pga_gain(gain, 'B'); +    return _dbc[db].codec->get_rx_pga_gain('A');  } diff --git a/host/lib/usrp/usrp1/usrp1_impl.hpp b/host/lib/usrp/usrp1/usrp1_impl.hpp index bea1dbe3b..cb1497253 100644 --- a/host/lib/usrp/usrp1/usrp1_impl.hpp +++ b/host/lib/usrp/usrp1/usrp1_impl.hpp @@ -16,48 +16,27 @@  //  #include "usrp1_iface.hpp" -#include "clock_ctrl.hpp"  #include "codec_ctrl.hpp"  #include "soft_time_ctrl.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 <boost/thread/barrier.hpp>  #include <uhd/transport/usb_zero_copy.hpp>  #ifndef INCLUDED_USRP1_IMPL_HPP  #define INCLUDED_USRP1_IMPL_HPP  /*! - * 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... @@ -73,9 +52,7 @@ public:      static const std::vector<dboard_slot_t> _dboard_slots;      //structors -    usrp1_impl(uhd::transport::usb_zero_copy::sptr data_transport, -               uhd::usrp::fx2_ctrl::sptr ctrl_transport); - +    usrp1_impl(const uhd::device_addr_t &);      ~usrp1_impl(void);      //the io interface @@ -97,125 +74,73 @@ public:      bool recv_async_msg(uhd::async_metadata_t &, double);  private: -    /*! -     * 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( -        usrp1_iface::sptr iface, -        usrp1_clock_ctrl::sptr clock, -        usrp1_codec_ctrl::sptr codec, -        dboard_slot_t dboard_slot, -        const uhd::usrp::dboard_id_t &rx_dboard_id -    ); +    uhd::property_tree::sptr _tree; -    //!call when the channel mapping is changed -    void update_xport_channel_mapping(void); +    //device properties interface +    void get(const wax::obj &, wax::obj &val){ +        val = _tree; //entry point into property tree +    } -    //soft time control emulation +    //controllers +    uhd::usrp::fx2_ctrl::sptr _fx2_ctrl; +    usrp1_iface::sptr _iface;      uhd::usrp::soft_time_ctrl::sptr _soft_time_ctrl; +    uhd::transport::usb_zero_copy::sptr _data_transport; +    struct db_container_type{ +        usrp1_codec_ctrl::sptr codec; +        uhd::usrp::dboard_iface::sptr dboard_iface; +        uhd::usrp::dboard_manager::sptr dboard_manager; +    }; +    uhd::dict<std::string, db_container_type> _dbc; -    //interface to ioctls and file descriptor -    usrp1_iface::sptr _iface; +    double _master_clock_rate; //clock rate shadow + +    void set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &); +    void set_db_eeprom(const std::string &, const std::string &, const uhd::usrp::dboard_eeprom_t &); +    double update_rx_codec_gain(const std::string &, const double); //sets A and B at once +    void update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &); +    void update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &); +    double update_rx_samp_rate(const double); +    double update_tx_samp_rate(const double); +    double update_rx_dsp_freq(const size_t, const double); +    double update_tx_dsp_freq(const size_t, const double); + +    static uhd::usrp::dboard_iface::sptr make_dboard_iface( +        usrp1_iface::sptr, +        usrp1_codec_ctrl::sptr, +        dboard_slot_t, +        const double, +        const uhd::usrp::dboard_id_t & +    );      //handle io stuff      UHD_PIMPL_DECL(io_impl) _io_impl;      void io_init(void);      void rx_stream_on_off(bool); +    void tx_stream_on_off(bool);      void handle_overrun(size_t); -    //underrun and overrun poll intervals -    size_t _rx_samps_per_poll_interval; -    size_t _tx_samps_per_poll_interval;  -      //otw types -    uhd::otw_type_t _rx_otw_type; -    uhd::otw_type_t _tx_otw_type; - -    //configuration shadows +    uhd::otw_type_t _rx_otw_type, _tx_otw_type;      uhd::usrp::subdev_spec_t _rx_subdev_spec, _tx_subdev_spec; -    //clock control -    usrp1_clock_ctrl::sptr _clock_ctrl; - -    //ad9862 codec control interface -    uhd::dict<dboard_slot_t, usrp1_codec_ctrl::sptr> _codec_ctrls; - -    //codec properties interfaces -    void codec_init(void); -    void rx_codec_get(const wax::obj &, wax::obj &, dboard_slot_t); -    void rx_codec_set(const wax::obj &, const wax::obj &, dboard_slot_t); -    void tx_codec_get(const wax::obj &, wax::obj &, dboard_slot_t); -    void tx_codec_set(const wax::obj &, const wax::obj &, dboard_slot_t); -    uhd::dict<dboard_slot_t, wax_obj_proxy::sptr> _rx_codec_proxies, _tx_codec_proxies; - -    //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 &); -    wax_obj_proxy::sptr _mboard_proxy; - -    //xx dboard functions and settings -    void dboard_init(void); -    uhd::dict<dboard_slot_t, uhd::usrp::dboard_manager::sptr> _dboard_managers; -    uhd::dict<dboard_slot_t, uhd::usrp::dboard_iface::sptr> _dboard_ifaces; - -    //rx dboard functions and settings -    uhd::dict<dboard_slot_t, uhd::usrp::dboard_eeprom_t> _rx_db_eeproms; -    void rx_dboard_get(const wax::obj &, wax::obj &, dboard_slot_t); -    void rx_dboard_set(const wax::obj &, const wax::obj &, dboard_slot_t); -    uhd::dict<dboard_slot_t, wax_obj_proxy::sptr> _rx_dboard_proxies; - -    //tx dboard functions and settings -    uhd::dict<dboard_slot_t, uhd::usrp::dboard_eeprom_t> _tx_db_eeproms, _gdb_eeproms; -    void tx_dboard_get(const wax::obj &, wax::obj &, dboard_slot_t); -    void tx_dboard_set(const wax::obj &, const wax::obj &, dboard_slot_t); -    uhd::dict<dboard_slot_t, wax_obj_proxy::sptr> _tx_dboard_proxies; - -    //rx dsp functions and settings -    void rx_dsp_init(void); -    void rx_dsp_get(const wax::obj &, wax::obj &, size_t); -    void rx_dsp_set(const wax::obj &, const wax::obj &, size_t); -    uhd::dict<size_t, double> _rx_dsp_freqs; -    size_t _rx_dsp_decim; -    uhd::dict<std::string, wax_obj_proxy::sptr> _rx_dsp_proxies; - -    //tx dsp functions and settings -    void tx_dsp_init(void); -    void tx_dsp_get(const wax::obj &, wax::obj &, size_t); -    void tx_dsp_set(const wax::obj &, const wax::obj &, size_t); -    uhd::dict<size_t, double> _tx_dsp_freqs; -    size_t _tx_dsp_interp; -    uhd::dict<std::string, wax_obj_proxy::sptr> _tx_dsp_proxies; - -    //transports -    uhd::transport::usb_zero_copy::sptr _data_transport; -    uhd::usrp::fx2_ctrl::sptr _ctrl_transport; -      //capabilities      size_t get_num_ducs(void);      size_t get_num_ddcs(void);      bool has_rx_halfband(void);      bool has_tx_halfband(void); +    void vandal_conquest_loop(boost::barrier &); +      //handle the enables      bool _rx_enabled, _tx_enabled;      void enable_rx(bool enb){          _rx_enabled = enb; -        _ctrl_transport->usrp_rx_enable(enb); +        _fx2_ctrl->usrp_rx_enable(enb);      }      void enable_tx(bool enb){          _tx_enabled = enb; -        _ctrl_transport->usrp_tx_enable(enb); +        _fx2_ctrl->usrp_tx_enable(enb);      }      //conditionally disable and enable rx diff --git a/host/lib/usrp/usrp2/CMakeLists.txt b/host/lib/usrp/usrp2/CMakeLists.txt index c3f138c24..10f7407b0 100644 --- a/host/lib/usrp/usrp2/CMakeLists.txt +++ b/host/lib/usrp/usrp2/CMakeLists.txt @@ -1,5 +1,5 @@  # -# Copyright 2010-2011 Ettus Research LLC +# 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 @@ -27,19 +27,10 @@ LIBUHD_REGISTER_COMPONENT("USRP2" ENABLE_USRP2 ON "ENABLE_LIBUHD" OFF)  IF(ENABLE_USRP2)      LIBUHD_APPEND_SOURCES(          ${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}/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}/usrp2_iface.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/usrp2_iface.hpp          ${CMAKE_CURRENT_SOURCE_DIR}/usrp2_impl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/usrp2_impl.hpp -        ${CMAKE_CURRENT_SOURCE_DIR}/usrp2_regs.hpp      )  ENDIF(ENABLE_USRP2) diff --git a/host/lib/usrp/usrp2/codec_impl.cpp b/host/lib/usrp/usrp2/codec_impl.cpp deleted file mode 100644 index 26da42759..000000000 --- a/host/lib/usrp/usrp2/codec_impl.cpp +++ /dev/null @@ -1,181 +0,0 @@ -// -// Copyright 2010-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 "usrp2_impl.hpp" -#include <uhd/utils/assert_has.hpp> -#include <uhd/exception.hpp> -#include <uhd/usrp/codec_props.hpp> -#include <uhd/types/dict.hpp> -#include <uhd/types/ranges.hpp> -#include <boost/bind.hpp> -#include <boost/assign/list_of.hpp> - -using namespace uhd; -using namespace uhd::usrp; -using namespace boost::assign; - -//this only applies to N2XX -static const uhd::dict<std::string, gain_range_t> codec_rx_gain_ranges = map_list_of -                                  ("digital", gain_range_t(0, 6.0, 0.5)) -                                  ("digital-fine", gain_range_t(0, 0.5, 0.05)); - - -/*********************************************************************** - * Helper Methods - **********************************************************************/ -void usrp2_mboard_impl::codec_init(void){ -    //make proxies -    _rx_codec_proxy = wax_obj_proxy::make( -        boost::bind(&usrp2_mboard_impl::rx_codec_get, this, _1, _2), -        boost::bind(&usrp2_mboard_impl::rx_codec_set, this, _1, _2) -    ); -    _tx_codec_proxy = wax_obj_proxy::make( -        boost::bind(&usrp2_mboard_impl::tx_codec_get, this, _1, _2), -        boost::bind(&usrp2_mboard_impl::tx_codec_set, this, _1, _2) -    ); -     -    //initialize gain names. keeps get_rx_gain() from getting a gain  -    //that hasn't been set yet. -    BOOST_FOREACH(std::string key, codec_rx_gain_ranges.keys()) { -        _codec_rx_gains[key] = codec_rx_gain_ranges[key].start(); -    } -} - -/*********************************************************************** - * RX Codec Properties - **********************************************************************/ -void usrp2_mboard_impl::rx_codec_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_NAME: -        switch(_iface->get_rev()){ -        case usrp2_iface::USRP_N200: -        case usrp2_iface::USRP_N210: -        case usrp2_iface::USRP_N200_R4: -        case usrp2_iface::USRP_N210_R4: -            val = _iface->get_cname() + " adc - ads62p44"; -            break; - -        case usrp2_iface::USRP2_REV3: -        case usrp2_iface::USRP2_REV4: -            val = _iface->get_cname() + " adc - ltc2284"; -            break; - -        case usrp2_iface::USRP_NXXX: -            val = _iface->get_cname() + " adc - ??????"; -            break; -        } -        return; - -    case CODEC_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case CODEC_PROP_GAIN_NAMES: -        switch(_iface->get_rev()){ -        case usrp2_iface::USRP_N200: -        case usrp2_iface::USRP_N210: -            val = prop_names_t(codec_rx_gain_ranges.keys()); -            return; - -        default: val = prop_names_t(); -        } -        return; - -    case CODEC_PROP_GAIN_I: -    case CODEC_PROP_GAIN_Q: -        assert_has(_codec_rx_gains.keys(), key.name, "codec rx gain name"); -        val = _codec_rx_gains[key.name]; -        return; - -    case CODEC_PROP_GAIN_RANGE: -      assert_has(codec_rx_gain_ranges.keys(), key.name, "codec rx gain range name"); -      val = codec_rx_gain_ranges[key.name]; -      return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void usrp2_mboard_impl::rx_codec_set(const wax::obj &key_, const wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<codec_prop_t>()) { -    case CODEC_PROP_GAIN_I: -    case CODEC_PROP_GAIN_Q: -        this->rx_codec_set_gain(val.as<double>(), key.name); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -  } -} - -/*********************************************************************** - * Helper function to set RX codec gain - ***********************************************************************/ - -void usrp2_mboard_impl::rx_codec_set_gain(double gain, const std::string &name){ -  assert_has(codec_rx_gain_ranges.keys(), name, "codec rx gain name"); - -  _codec_rx_gains[name] = gain; -/* -  if(name == "analog") { -    _codec_ctrl->set_rx_analog_gain(gain > 0); //just turn it on or off -    return; -  } -*/ -  if(name == "digital") { -    _codec_ctrl->set_rx_digital_gain(gain); -    return; -  } -  if(name == "digital-fine") { -    _codec_ctrl->set_rx_digital_fine_gain(gain); -    return; -  } -  UHD_THROW_PROP_SET_ERROR(); -} - - -/*********************************************************************** - * TX Codec Properties - **********************************************************************/ -void usrp2_mboard_impl::tx_codec_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<codec_prop_t>()){ -    case CODEC_PROP_NAME: -        val = _iface->get_cname() + " dac - ad9777"; -        return; - -    case CODEC_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case CODEC_PROP_GAIN_NAMES: -        val = prop_names_t(); //no gain elements to be controlled -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void usrp2_mboard_impl::tx_codec_set(const wax::obj &, const wax::obj &){ -    UHD_THROW_PROP_SET_ERROR(); -} diff --git a/host/lib/usrp/usrp2/dboard_impl.cpp b/host/lib/usrp/usrp2/dboard_impl.cpp deleted file mode 100644 index 8c6379d66..000000000 --- a/host/lib/usrp/usrp2/dboard_impl.cpp +++ /dev/null @@ -1,183 +0,0 @@ -// -// Copyright 2010-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 "usrp2_impl.hpp" -#include "usrp2_regs.hpp" -#include "fw_common.h" -#include <uhd/usrp/misc_utils.hpp> -#include <uhd/usrp/dsp_utils.hpp> -#include <uhd/usrp/subdev_props.hpp> -#include <uhd/usrp/dboard_props.hpp> -#include <uhd/exception.hpp> -#include <boost/format.hpp> -#include <boost/bind.hpp> -#include <boost/asio.hpp> //htonl and ntohl -#include <iostream> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * Helper Methods - **********************************************************************/ -void usrp2_mboard_impl::dboard_init(void){ -    //read the dboard eeprom to extract the dboard ids -    _rx_db_eeprom.load(*_iface, USRP2_I2C_ADDR_RX_DB); -    _tx_db_eeprom.load(*_iface, USRP2_I2C_ADDR_TX_DB); -    _gdb_eeprom.load(*_iface, USRP2_I2C_ADDR_TX_DB ^ 5); - -    //create a new dboard interface and manager -    _dboard_iface = make_usrp2_dboard_iface(_iface, _clock_ctrl); -    _dboard_manager = dboard_manager::make( -        _rx_db_eeprom.id, -        ((_gdb_eeprom.id == dboard_id_t::none())? _tx_db_eeprom : _gdb_eeprom).id, -        _dboard_iface -    ); - -    //load dboards -    _rx_dboard_proxy = wax_obj_proxy::make( -        boost::bind(&usrp2_mboard_impl::rx_dboard_get, this, _1, _2), -        boost::bind(&usrp2_mboard_impl::rx_dboard_set, this, _1, _2) -    ); -    _tx_dboard_proxy = wax_obj_proxy::make( -        boost::bind(&usrp2_mboard_impl::tx_dboard_get, this, _1, _2), -        boost::bind(&usrp2_mboard_impl::tx_dboard_set, this, _1, _2) -    ); -} - -/*********************************************************************** - * RX DBoard Properties - **********************************************************************/ -void usrp2_mboard_impl::rx_dboard_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_NAME: -        val = _iface->get_cname() + " dboard (rx unit)"; -        return; - -    case DBOARD_PROP_SUBDEV: -        val = _dboard_manager->get_rx_subdev(key.name); -        return; - -    case DBOARD_PROP_SUBDEV_NAMES: -        val = _dboard_manager->get_rx_subdev_names(); -        return; - -    case DBOARD_PROP_DBOARD_EEPROM: -        val = _rx_db_eeprom; -        return; - -    case DBOARD_PROP_DBOARD_IFACE: -        val = _dboard_iface; -        return; - -    case DBOARD_PROP_CODEC: -        val = _rx_codec_proxy->get_link(); -        return; - -    case DBOARD_PROP_GAIN_GROUP: -        val = make_gain_group( -            _rx_db_eeprom.id, -            _dboard_manager->get_rx_subdev(key.name), -            _rx_codec_proxy->get_link(), -            GAIN_GROUP_POLICY_RX -        ); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void usrp2_mboard_impl::rx_dboard_set(const wax::obj &key, const wax::obj &val){ -    switch(key.as<dboard_prop_t>()){ - -    case DBOARD_PROP_DBOARD_EEPROM: -        _rx_db_eeprom = val.as<dboard_eeprom_t>(); -        _rx_db_eeprom.store(*_iface, USRP2_I2C_ADDR_RX_DB); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} - -/*********************************************************************** - * TX DBoard Properties - **********************************************************************/ -void usrp2_mboard_impl::tx_dboard_get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); - -    //handle the get request conditioned on the key -    switch(key.as<dboard_prop_t>()){ -    case DBOARD_PROP_NAME: -        val = _iface->get_cname() + " dboard (tx unit)"; -        return; - -    case DBOARD_PROP_SUBDEV: -        val = _dboard_manager->get_tx_subdev(key.name); -        return; - -    case DBOARD_PROP_SUBDEV_NAMES: -        val = _dboard_manager->get_tx_subdev_names(); -        return; - -    case DBOARD_PROP_DBOARD_EEPROM: -        val = _tx_db_eeprom; -        return; - -    case DBOARD_PROP_GBOARD_EEPROM: -        val = _gdb_eeprom; -        return; - -    case DBOARD_PROP_DBOARD_IFACE: -        val = _dboard_iface; -        return; - -    case DBOARD_PROP_CODEC: -        val = _tx_codec_proxy->get_link(); -        return; - -    case DBOARD_PROP_GAIN_GROUP: -        val = make_gain_group( -            _tx_db_eeprom.id, -            _dboard_manager->get_tx_subdev(key.name), -            _tx_codec_proxy->get_link(), -            GAIN_GROUP_POLICY_TX -        ); -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void usrp2_mboard_impl::tx_dboard_set(const wax::obj &key, const wax::obj &val){ -    switch(key.as<dboard_prop_t>()){ - -    case DBOARD_PROP_DBOARD_EEPROM: -        _tx_db_eeprom = val.as<dboard_eeprom_t>(); -        _tx_db_eeprom.store(*_iface, USRP2_I2C_ADDR_TX_DB); -        return; - -    case DBOARD_PROP_GBOARD_EEPROM: -        _gdb_eeprom = val.as<dboard_eeprom_t>(); -        _gdb_eeprom.store(*_iface, USRP2_I2C_ADDR_TX_DB ^ 5); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/usrp2/dsp_impl.cpp b/host/lib/usrp/usrp2/dsp_impl.cpp deleted file mode 100644 index d9cde3f13..000000000 --- a/host/lib/usrp/usrp2/dsp_impl.cpp +++ /dev/null @@ -1,256 +0,0 @@ -// -// Copyright 2010-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 "usrp2_impl.hpp" -#include "usrp2_regs.hpp" -#include <uhd/usrp/dsp_utils.hpp> -#include <uhd/usrp/dsp_props.hpp> -#include <boost/bind.hpp> -#include <boost/math/special_functions/round.hpp> -#include <boost/math/special_functions/sign.hpp> -#include <algorithm> -#include <cmath> - -using namespace uhd; -using namespace uhd::usrp; - -/*********************************************************************** - * DSP impl and methods - **********************************************************************/ -struct usrp2_mboard_impl::dsp_impl{ -    uhd::dict<size_t, size_t> ddc_decim; -    uhd::dict<size_t, double> ddc_freq; -    uhd::dict<size_t, size_t> duc_interp; -    uhd::dict<size_t, double> duc_freq; -    std::vector<size_t> decim_and_interp_rates; -    uhd::dict<size_t, bool> continuous_streaming; -}; - -void usrp2_mboard_impl::dsp_init(void){ -    //create new dsp impl -    _dsp_impl = UHD_PIMPL_MAKE(dsp_impl, ()); - -    //load the allowed decim/interp rates -    //range(4, 128+1, 1) + range(130, 256+1, 2) + range(260, 512+1, 4) -    for (size_t i = 4; i <= 128; i+=1){ -        _dsp_impl->decim_and_interp_rates.push_back(i); -    } -    for (size_t i = 130; i <= 256; i+=2){ -        _dsp_impl->decim_and_interp_rates.push_back(i); -    } -    for (size_t i = 260; i <= 512; i+=4){ -        _dsp_impl->decim_and_interp_rates.push_back(i); -    } - -    //bind and initialize the rx dsps -    for (size_t i = 0; i < NUM_RX_DSPS; i++){ -        _rx_dsp_proxies[str(boost::format("DSP%d")%i)] = wax_obj_proxy::make( -            boost::bind(&usrp2_mboard_impl::ddc_get, this, _1, _2, i), -            boost::bind(&usrp2_mboard_impl::ddc_set, this, _1, _2, i) -        ); - -        //initial config and update -        ddc_set(DSP_PROP_FREQ_SHIFT, double(0), i); -        ddc_set(DSP_PROP_HOST_RATE, double(get_master_clock_freq()/16), i); - -        //setup the rx control registers -        _iface->poke32(U2_REG_RX_CTRL_CLEAR(i), 1); //reset -        _iface->poke32(U2_REG_RX_CTRL_NSAMPS_PP(i), _device.get_max_recv_samps_per_packet()); -        _iface->poke32(U2_REG_RX_CTRL_NCHANNELS(i), 1); -        _iface->poke32(U2_REG_RX_CTRL_VRT_HDR(i), 0 -            | (0x1 << 28) //if data with stream id -            | (0x1 << 26) //has trailer -            | (0x3 << 22) //integer time other -            | (0x1 << 20) //fractional time sample count -        ); -        _iface->poke32(U2_REG_RX_CTRL_VRT_SID(i), usrp2_impl::RECV_SID); -        _iface->poke32(U2_REG_RX_CTRL_VRT_TLR(i), 0); -        _iface->poke32(U2_REG_TIME64_TPS, size_t(get_master_clock_freq())); -    } - -    //bind and initialize the tx dsps -    for (size_t i = 0; i < NUM_TX_DSPS; i++){ -        _tx_dsp_proxies[str(boost::format("DSP%d")%i)] = wax_obj_proxy::make( -            boost::bind(&usrp2_mboard_impl::duc_get, this, _1, _2, i), -            boost::bind(&usrp2_mboard_impl::duc_set, this, _1, _2, i) -        ); - -        //initial config and update -        duc_set(DSP_PROP_FREQ_SHIFT, double(0), i); -        duc_set(DSP_PROP_HOST_RATE, double(get_master_clock_freq()/16), i); - -        //init the tx control registers -        _iface->poke32(U2_REG_TX_CTRL_CLEAR_STATE, 1); //reset -        _iface->poke32(U2_REG_TX_CTRL_NUM_CHAN, 0);    //1 channel -        _iface->poke32(U2_REG_TX_CTRL_REPORT_SID, usrp2_impl::ASYNC_SID); -        _iface->poke32(U2_REG_TX_CTRL_POLICY, U2_FLAG_TX_CTRL_POLICY_NEXT_PACKET); -    } -} - -template <typename rate_type> -static rate_type pick_closest_rate(double exact_rate, const std::vector<rate_type> &rates){ -    unsigned closest_match = rates.front(); -    BOOST_FOREACH(rate_type possible_rate, rates){ -        if(std::abs(exact_rate - possible_rate) < std::abs(exact_rate - closest_match)) -            closest_match = possible_rate; -    } -    return closest_match; -} - -void usrp2_mboard_impl::issue_ddc_stream_cmd(const stream_cmd_t &stream_cmd, size_t which_dsp){ -    _dsp_impl->continuous_streaming[which_dsp] = stream_cmd.stream_mode == stream_cmd_t::STREAM_MODE_START_CONTINUOUS; -    _iface->poke32(U2_REG_RX_CTRL_STREAM_CMD(which_dsp), dsp_type1::calc_stream_cmd_word(stream_cmd)); -    _iface->poke32(U2_REG_RX_CTRL_TIME_SECS(which_dsp),  boost::uint32_t(stream_cmd.time_spec.get_full_secs())); -    _iface->poke32(U2_REG_RX_CTRL_TIME_TICKS(which_dsp), stream_cmd.time_spec.get_tick_count(get_master_clock_freq())); -} - -/*********************************************************************** - * DDC Properties - **********************************************************************/ -void usrp2_mboard_impl::ddc_get(const wax::obj &key_, wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ -    case DSP_PROP_NAME: -        val = str(boost::format("%s ddc%d") % _iface->get_cname() % which_dsp); -        return; - -    case DSP_PROP_OTHERS: -        val = prop_names_t(); //empty -        return; - -    case DSP_PROP_FREQ_SHIFT: -        val = _dsp_impl->ddc_freq[which_dsp]; -        return; - -    case DSP_PROP_CODEC_RATE: -        val = get_master_clock_freq(); -        return; - -    case DSP_PROP_HOST_RATE: -        val = get_master_clock_freq()/_dsp_impl->ddc_decim[which_dsp]; -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void usrp2_mboard_impl::ddc_set(const wax::obj &key_, const wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ - -    case DSP_PROP_STREAM_CMD: -        issue_ddc_stream_cmd(val.as<stream_cmd_t>(), which_dsp); -        return; - -    case DSP_PROP_FREQ_SHIFT:{ -            double new_freq = val.as<double>(); -            _iface->poke32(U2_REG_DSP_RX_FREQ(which_dsp), -                dsp_type1::calc_cordic_word_and_update(new_freq, get_master_clock_freq()) -            ); -            _dsp_impl->ddc_freq[which_dsp] = new_freq; //shadow -        } -        return; - -    case DSP_PROP_HOST_RATE:{ -            double extact_rate = get_master_clock_freq()/val.as<double>(); -            _dsp_impl->ddc_decim[which_dsp] = pick_closest_rate(extact_rate, _dsp_impl->decim_and_interp_rates); - -            //set the decimation -            _iface->poke32(U2_REG_DSP_RX_DECIM(which_dsp), dsp_type1::calc_cic_filter_word(_dsp_impl->ddc_decim[which_dsp])); -        } -        _device.update_xport_channel_mapping(); //rate changed -> update -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} - -/*********************************************************************** - * DUC Properties - **********************************************************************/ -void usrp2_mboard_impl::duc_get(const wax::obj &key_, wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ -    case DSP_PROP_NAME: -        val = str(boost::format("%s duc%d") % _iface->get_cname() % which_dsp); -        return; - -    case DSP_PROP_OTHERS: -        val = prop_names_t(); //empty -        return; - -    case DSP_PROP_FREQ_SHIFT: -        val = _dsp_impl->duc_freq[which_dsp]; -        return; - -    case DSP_PROP_CODEC_RATE: -        val = get_master_clock_freq(); -        return; - -    case DSP_PROP_HOST_RATE: -        val = get_master_clock_freq()/_dsp_impl->duc_interp[which_dsp]; -        return; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -void usrp2_mboard_impl::duc_set(const wax::obj &key_, const wax::obj &val, size_t which_dsp){ -    named_prop_t key = named_prop_t::extract(key_); - -    switch(key.as<dsp_prop_t>()){ - -    case DSP_PROP_FREQ_SHIFT:{ -            const double codec_rate = get_master_clock_freq(); -            double new_freq = val.as<double>(); - -            //calculate the DAC shift (multiples of rate) -            const int sign = boost::math::sign(new_freq); -            const int zone = std::min(boost::math::iround(new_freq/codec_rate), 2); -            const double dac_shift = sign*zone*codec_rate; -            new_freq -= dac_shift; //update FPGA DSP target freq - -            //set the DAC shift (modulation mode) -            if (zone == 0) _codec_ctrl->set_tx_mod_mode(0); //no shift -            else _codec_ctrl->set_tx_mod_mode(sign*4/zone); //DAC interp = 4 - -            _iface->poke32(U2_REG_DSP_TX_FREQ, -                dsp_type1::calc_cordic_word_and_update(new_freq, codec_rate) -            ); -            _dsp_impl->duc_freq[which_dsp] = new_freq + dac_shift; //shadow -        } -        return; - -    case DSP_PROP_HOST_RATE:{ -            double extact_rate = get_master_clock_freq()/val.as<double>(); -            _dsp_impl->duc_interp[which_dsp] = pick_closest_rate(extact_rate, _dsp_impl->decim_and_interp_rates); - -            //set the interpolation -            _iface->poke32(U2_REG_DSP_TX_INTERP_RATE, dsp_type1::calc_cic_filter_word(_dsp_impl->duc_interp[which_dsp])); - -            //set the scaling -            _iface->poke32(U2_REG_DSP_TX_SCALE_IQ, dsp_type1::calc_iq_scale_word(_dsp_impl->duc_interp[which_dsp])); -        } -        _device.update_xport_channel_mapping(); //rate changed -> update -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/usrp2/io_impl.cpp b/host/lib/usrp/usrp2/io_impl.cpp index df452942c..eda2267bc 100644 --- a/host/lib/usrp/usrp2/io_impl.cpp +++ b/host/lib/usrp/usrp2/io_impl.cpp @@ -15,6 +15,7 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // +#include "validate_subdev_spec.hpp"  #include "../../transport/super_recv_packet_handler.hpp"  #include "../../transport/super_send_packet_handler.hpp"  #include "usrp2_impl.hpp" @@ -22,8 +23,6 @@  #include <uhd/utils/log.hpp>  #include <uhd/utils/msg.hpp>  #include <uhd/exception.hpp> -#include <uhd/usrp/mboard_props.hpp> -#include <uhd/usrp/dsp_props.hpp>  #include <uhd/utils/byteswap.hpp>  #include <uhd/utils/thread_priority.hpp>  #include <uhd/transport/bounded_buffer.hpp> @@ -54,11 +53,6 @@ static UHD_INLINE double from_time_dur(const pt::time_duration &time_dur){  /***********************************************************************   * constants   **********************************************************************/ -static const int underflow_flags = 0 -    | async_metadata_t::EVENT_CODE_UNDERFLOW -    | async_metadata_t::EVENT_CODE_UNDERFLOW_IN_PACKET -; -  static const size_t vrt_send_header_offset_words32 = 1;  /*********************************************************************** @@ -134,15 +128,10 @@ private:   **********************************************************************/  struct usrp2_impl::io_impl{ -    io_impl(std::vector<zero_copy_if::sptr> &dsp_xports): -        dsp_xports(dsp_xports), //the assumption is that all data transports should be identical +    io_impl(void):          async_msg_fifo(100/*messages deep*/)      { -        for (size_t i = 0; i < dsp_xports.size(); i++){ -            fc_mons.push_back(flow_control_monitor::sptr(new flow_control_monitor( -                usrp2_impl::sram_bytes/dsp_xports.front()->get_send_frame_size() -            ))); -        } +        /* NOP */      }      ~io_impl(void){ @@ -151,14 +140,13 @@ struct usrp2_impl::io_impl{      }      managed_send_buffer::sptr get_send_buff(size_t chan, double timeout){ -        const size_t index = send_map[chan]; -        flow_control_monitor &fc_mon = *fc_mons[index]; +        flow_control_monitor &fc_mon = *fc_mons[chan];          //wait on flow control w/ timeout          if (not fc_mon.check_fc_condition(timeout)) return managed_send_buffer::sptr();          //get a buffer from the transport w/ timeout -        managed_send_buffer::sptr buff = dsp_xports[index]->get_send_buff(timeout); +        managed_send_buffer::sptr buff = tx_xports[chan]->get_send_buff(timeout);          //write the flow control word into the buffer          if (buff.get()) buff->cast<boost::uint32_t *>()[0] = uhd::htonx(fc_mon.get_curr_seq_out()); @@ -166,15 +154,8 @@ struct usrp2_impl::io_impl{          return buff;      } -    std::vector<zero_copy_if::sptr> &dsp_xports; - -    //mappings from channel index to dsp xport -    std::vector<size_t> send_map, recv_map; - -    //previous state for each buffer -    std::vector<vrt::if_packet_info_t> prev_infos; - -    //flow control monitors +    //tx dsp: xports and flow control monitors +    std::vector<zero_copy_if::sptr> tx_xports;      std::vector<flow_control_monitor::sptr> fc_mons;      //state management for the vrt packet handler code @@ -182,9 +163,10 @@ struct usrp2_impl::io_impl{      sph::send_packet_handler send_handler;      //methods and variables for the pirate crew -    void recv_pirate_loop(boost::barrier &, usrp2_mboard_impl::sptr, zero_copy_if::sptr, size_t); +    void recv_pirate_loop(boost::barrier &, zero_copy_if::sptr, size_t);      boost::thread_group recv_pirate_crew;      bounded_buffer<async_metadata_t> async_msg_fifo; +    double tick_rate;  };  /*********************************************************************** @@ -195,7 +177,6 @@ struct usrp2_impl::io_impl{   **********************************************************************/  void usrp2_impl::io_impl::recv_pirate_loop(      boost::barrier &spawn_barrier, -    usrp2_mboard_impl::sptr mboard,      zero_copy_if::sptr err_xport,      size_t index  ){ @@ -203,7 +184,7 @@ void usrp2_impl::io_impl::recv_pirate_loop(      set_thread_priority_safe();      //store a reference to the flow control monitor (offset by max dsps) -    flow_control_monitor &fc_mon = *(this->fc_mons[index*usrp2_mboard_impl::MAX_NUM_DSPS]); +    flow_control_monitor &fc_mon = *(this->fc_mons[index]);      while (not boost::this_thread::interruption_requested()){          managed_recv_buffer::sptr buff = err_xport->get_recv_buff(); @@ -217,14 +198,14 @@ void usrp2_impl::io_impl::recv_pirate_loop(              vrt::if_hdr_unpack_be(vrt_hdr, if_packet_info);              //handle a tx async report message -            if (if_packet_info.sid == usrp2_impl::ASYNC_SID and if_packet_info.packet_type != vrt::if_packet_info_t::PACKET_TYPE_DATA){ +            if (if_packet_info.sid == USRP2_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;                  metadata.channel = index;                  metadata.has_time_spec = if_packet_info.has_tsi and if_packet_info.has_tsf;                  metadata.time_spec = time_spec_t( -                    time_t(if_packet_info.tsi), size_t(if_packet_info.tsf), mboard->get_master_clock_freq() +                    time_t(if_packet_info.tsi), size_t(if_packet_info.tsf), tick_rate                  );                  metadata.event_code = async_metadata_t::event_code_t(sph::get_context_code(vrt_hdr, if_packet_info)); @@ -234,11 +215,17 @@ void usrp2_impl::io_impl::recv_pirate_loop(                      fc_mon.update_fc_condition(uhd::ntohx(fc_word32));                      continue;                  } - -                //print the famous U, and push the metadata into the message queue -                if (metadata.event_code & underflow_flags) UHD_MSG(fastpath) << "U";                  //else UHD_MSG(often) << "metadata.event_code " << metadata.event_code << std::endl;                  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_IN_PACKET) +                ) UHD_MSG(fastpath) << "U"; +                else if (metadata.event_code & +                    ( async_metadata_t::EVENT_CODE_SEQ_ERROR +                    | async_metadata_t::EVENT_CODE_SEQ_ERROR_IN_BURST) +                ) UHD_MSG(fastpath) << "S";              }              else{                  //TODO unknown received packet, may want to print error... @@ -254,80 +241,151 @@ void usrp2_impl::io_impl::recv_pirate_loop(   **********************************************************************/  void usrp2_impl::io_init(void){ +    //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; +      //create new io impl -    _io_impl = UHD_PIMPL_MAKE(io_impl, (dsp_xports)); +    _io_impl = UHD_PIMPL_MAKE(io_impl, ()); + +    //init first so we dont have an access race +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        //init the tx xport and flow control monitor +        _io_impl->tx_xports.push_back(_mbc[mb].dsp_xports.at(0)); +        _io_impl->fc_mons.push_back(flow_control_monitor::sptr(new flow_control_monitor( +            USRP2_SRAM_BYTES/_mbc[mb].dsp_xports.at(0)->get_send_frame_size() +        ))); +    }      //create a new pirate thread for each zc if (yarr!!) -    boost::barrier spawn_barrier(_mboards.size()+1); -    for (size_t i = 0; i < _mboards.size(); i++){ +    boost::barrier spawn_barrier(_mbc.size()+1); +    size_t index = 0; +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){          //spawn a new pirate to plunder the recv booty          _io_impl->recv_pirate_crew.create_thread(boost::bind(              &usrp2_impl::io_impl::recv_pirate_loop,              _io_impl.get(), boost::ref(spawn_barrier), -            _mboards.at(i), err_xports.at(i), i +            _mbc[mb].err_xports.at(0), index++          ));      }      spawn_barrier.wait(); -    //update mapping here since it didnt b4 when io init not called first -    update_xport_channel_mapping(); -} +    //init some handler stuff +    _io_impl->recv_handler.set_vrt_unpacker(&vrt::if_hdr_unpack_be); +    _io_impl->recv_handler.set_converter(_rx_otw_type); +    _io_impl->send_handler.set_vrt_packer(&vrt::if_hdr_pack_be, vrt_send_header_offset_words32); +    _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 usrp2_impl::update_xport_channel_mapping(void){ -    if (_io_impl.get() == NULL) return; //not inited yet +    //set the packet threshold to be an entire socket buffer's worth +    const size_t packets_per_sock_buff = 50e6/_mbc[_mbc.keys().front()].dsp_xports[0]->get_recv_frame_size(); +    _io_impl->recv_handler.set_alignment_failure_threshold(packets_per_sock_buff); +} -    _io_impl->recv_map.clear(); -    _io_impl->send_map.clear(); +void usrp2_impl::update_tick_rate(const double rate){ +    _io_impl->tick_rate = rate; +    boost::mutex::scoped_lock recv_lock = _io_impl->recv_handler.get_scoped_lock(); +    _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); +} -    for (size_t i = 0; i < _mboards.size(); i++){ +void usrp2_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); +} -        subdev_spec_t rx_subdev_spec = _mboards[i]->get_link()[MBOARD_PROP_RX_SUBDEV_SPEC].as<subdev_spec_t>(); -        for (size_t j = 0; j < rx_subdev_spec.size(); j++){ -            _io_impl->recv_map.push_back(i*usrp2_mboard_impl::MAX_NUM_DSPS+j); -            UHD_LOG << "recv_map.back() " << _io_impl->recv_map.back() << std::endl; -        } +void usrp2_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); +} -        subdev_spec_t tx_subdev_spec = _mboards[i]->get_link()[MBOARD_PROP_TX_SUBDEV_SPEC].as<subdev_spec_t>(); -        for (size_t j = 0; j < tx_subdev_spec.size(); j++){ -            _io_impl->send_map.push_back(i*usrp2_mboard_impl::MAX_NUM_DSPS+j); -            UHD_LOG << "send_map.back() " << _io_impl->send_map.back() << std::endl; +static subdev_spec_t replace_zero_in_spec(const std::string &type, const subdev_spec_t &spec){ +    subdev_spec_t new_spec; +    BOOST_FOREACH(const subdev_spec_pair_t &pair, spec){ +        if (pair.db_name == "0"){ +            UHD_MSG(warning) +                << boost::format("In the %s subdevice specification: %s") % type % spec.to_string() << std::endl +                << "Accepting dboard slot name \"0\" for backward compatibility." << std::endl +                << "The official name of the dboard slot on USRP2/N-Series is \"A\"." << std::endl +            ; +            new_spec.push_back(subdev_spec_pair_t("A", pair.sd_name));          } - +        else new_spec.push_back(pair);      } +    return new_spec; +} -    //set all of the relevant properties on the handler +subdev_spec_t usrp2_impl::update_rx_subdev_spec(const std::string &which_mb, const subdev_spec_t &spec_){ +    const subdev_spec_t spec = replace_zero_in_spec("RX", spec_);      boost::mutex::scoped_lock recv_lock = _io_impl->recv_handler.get_scoped_lock(); -    _io_impl->recv_handler.resize(_io_impl->recv_map.size()); -    _io_impl->recv_handler.set_vrt_unpacker(&vrt::if_hdr_unpack_be); -    _io_impl->recv_handler.set_tick_rate(_mboards.front()->get_master_clock_freq()); -    //TODO temporarily use the first dsp rate until we support non-homo rates -    const std::string rx_dsp_name = _mboards.at(0)->get_link()[MBOARD_PROP_RX_DSP_NAMES].as<prop_names_t>().at(0); -    const double rx_host_rate = _mboards.at(0)->get_link()[named_prop_t(MBOARD_PROP_RX_DSP, rx_dsp_name)][DSP_PROP_HOST_RATE].as<double>(); -    _io_impl->recv_handler.set_samp_rate(rx_host_rate); -    for (size_t chan = 0; chan < _io_impl->recv_handler.size(); chan++){ -        _io_impl->recv_handler.set_xport_chan_get_buff(chan, boost::bind( -            &uhd::transport::zero_copy_if::get_recv_buff, -            _io_impl->dsp_xports[_io_impl->recv_map[chan]], _1 -        )); +    property_tree::path_type root = "/mboards/" + which_mb + "/dboards"; + +    //sanity checking +    validate_subdev_spec(_tree, spec, "rx", which_mb); + +    //setup mux for this spec +    bool fe_swapped = false; +    for (size_t i = 0; i < spec.size(); i++){ +        const std::string conn = _tree->access<std::string>(root / spec[i].db_name / "rx_frontends" / spec[i].sd_name / "connection").get(); +        if (i == 0 and (conn == "QI" or conn == "Q")) fe_swapped = true; +        _mbc[which_mb].rx_dsps[i]->set_mux(conn, fe_swapped);      } -    _io_impl->recv_handler.set_converter(_rx_otw_type); +    _mbc[which_mb].rx_fe->set_mux(fe_swapped); + +    //compute the new occupancy and resize +    _mbc[which_mb].rx_chan_occ = spec.size(); +    size_t nchan = 0; +    BOOST_FOREACH(const std::string &mb, _mbc.keys()) nchan += _mbc[mb].rx_chan_occ; +    _io_impl->recv_handler.resize(nchan); + +    //bind new callbacks for the handler +    size_t chan = 0; +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        for (size_t dsp = 0; dsp < _mbc[mb].rx_chan_occ; dsp++){ +            _mbc[mb].rx_dsps[dsp]->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(chan++, boost::bind( +                &zero_copy_if::get_recv_buff, _mbc[mb].dsp_xports[dsp], _1 +            )); +        } +    } +    return spec; +} -    //set all of the relevant properties on the handler +subdev_spec_t usrp2_impl::update_tx_subdev_spec(const std::string &which_mb, const subdev_spec_t &spec_){ +    const subdev_spec_t spec = replace_zero_in_spec("TX", spec_);      boost::mutex::scoped_lock send_lock = _io_impl->send_handler.get_scoped_lock(); -    _io_impl->send_handler.resize(_io_impl->send_map.size()); -    _io_impl->send_handler.set_vrt_packer(&vrt::if_hdr_pack_be, vrt_send_header_offset_words32); -    _io_impl->send_handler.set_tick_rate(_mboards.front()->get_master_clock_freq()); -    //TODO temporarily use the first dsp rate until we support non-homo rates -    const std::string tx_dsp_name = _mboards.at(0)->get_link()[MBOARD_PROP_TX_DSP_NAMES].as<prop_names_t>().at(0); -    const double tx_host_rate = _mboards.at(0)->get_link()[named_prop_t(MBOARD_PROP_TX_DSP, tx_dsp_name)][DSP_PROP_HOST_RATE].as<double>(); -    _io_impl->send_handler.set_samp_rate(tx_host_rate); -    for (size_t chan = 0; chan < _io_impl->send_handler.size(); chan++){ -        _io_impl->send_handler.set_xport_chan_get_buff(chan, boost::bind( -            &usrp2_impl::io_impl::get_send_buff, _io_impl.get(), chan, _1 -        )); +    property_tree::path_type root = "/mboards/" + which_mb + "/dboards"; + +    //sanity checking +    validate_subdev_spec(_tree, spec, "tx", which_mb); + +    //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(); +    _mbc[which_mb].tx_fe->set_mux(conn); + +    //compute the new occupancy and resize +    _mbc[which_mb].tx_chan_occ = spec.size(); +    size_t nchan = 0; +    BOOST_FOREACH(const std::string &mb, _mbc.keys()) nchan += _mbc[mb].tx_chan_occ; +    _io_impl->send_handler.resize(nchan); + +    //bind new callbacks for the handler +    size_t chan = 0, i = 0; +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        for (size_t dsp = 0; dsp < _mbc[mb].tx_chan_occ; dsp++){ +            _io_impl->send_handler.set_xport_chan_get_buff(chan++, boost::bind( +                &usrp2_impl::io_impl::get_send_buff, _io_impl.get(), i++, _1 +            )); +        }      } -    _io_impl->send_handler.set_converter(_tx_otw_type); -    _io_impl->send_handler.set_max_samples_per_packet(get_max_send_samps_per_packet()); +    return spec;  }  /*********************************************************************** @@ -349,7 +407,7 @@ size_t usrp2_impl::get_max_send_samps_per_packet(void) const{          + vrt_send_header_offset_words32*sizeof(boost::uint32_t)          - sizeof(vrt::if_packet_info_t().cid) //no class id ever used      ; -    const size_t bpp = dsp_xports.front()->get_send_frame_size() - hdr_size; +    const size_t bpp = _mbc[_mbc.keys().front()].dsp_xports[0]->get_send_frame_size() - hdr_size;      return bpp/_tx_otw_type.get_sample_size();  } @@ -374,7 +432,7 @@ size_t usrp2_impl::get_max_recv_samps_per_packet(void) const{          + sizeof(vrt::if_packet_info_t().tlr) //forced to have trailer          - sizeof(vrt::if_packet_info_t().cid) //no class id ever used      ; -    const size_t bpp = dsp_xports.front()->get_recv_frame_size() - hdr_size; +    const size_t bpp = _mbc[_mbc.keys().front()].dsp_xports[0]->get_recv_frame_size() - hdr_size;      return bpp/_rx_otw_type.get_sample_size();  } diff --git a/host/lib/usrp/usrp2/mboard_impl.cpp b/host/lib/usrp/usrp2/mboard_impl.cpp deleted file mode 100644 index 5583a4335..000000000 --- a/host/lib/usrp/usrp2/mboard_impl.cpp +++ /dev/null @@ -1,522 +0,0 @@ -// -// Copyright 2010-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 "usrp2_impl.hpp" -#include "usrp2_regs.hpp" -#include "fw_common.h" -#include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> -#include <uhd/utils/safe_call.hpp> -#include <uhd/exception.hpp> -#include <uhd/usrp/gps_ctrl.hpp> -#include <uhd/usrp/misc_utils.hpp> -#include <uhd/usrp/dsp_utils.hpp> -#include <uhd/usrp/mboard_props.hpp> -#include <uhd/utils/byteswap.hpp> -#include <uhd/utils/algorithm.hpp> -#include <uhd/types/sensors.hpp> -#include <boost/assign/list_of.hpp> -#include <boost/bind.hpp> - -static const double mimo_clock_delay_usrp2_rev4 = 4.18e-9; -static const double mimo_clock_delay_usrp_n2xx = 3.55e-9; -static const size_t mimo_clock_sync_delay_cycles = 137; - -using namespace uhd; -using namespace uhd::usrp; -using namespace uhd::transport; - -/*********************************************************************** - * Helpers - **********************************************************************/ -static void init_xport(zero_copy_if::sptr xport){ -    //Send a small data packet so the usrp2 knows the udp source port. -    //This setup must happen before further initialization occurs -    //or the async update packets will cause ICMP destination unreachable. -    static const boost::uint32_t data[2] = { -        uhd::htonx(boost::uint32_t(0 /* don't care seq num */)), -        uhd::htonx(boost::uint32_t(USRP2_INVALID_VRT_HEADER)) -    }; - -    transport::managed_send_buffer::sptr send_buff = xport->get_send_buff(); -    std::memcpy(send_buff->cast<void*>(), &data, sizeof(data)); -    send_buff->commit(sizeof(data)); -} - -/*********************************************************************** - * Structors - **********************************************************************/ -usrp2_mboard_impl::usrp2_mboard_impl( -    const device_addr_t &device_addr, -    size_t index, usrp2_impl &device -): -    _index(index), _device(device), -    _iface(usrp2_iface::make(udp_simple::make_connected( -        device_addr["addr"], BOOST_STRINGIZE(USRP2_UDP_CTRL_PORT) -    ))) -{ - -    //check the fpga compatibility number -    const boost::uint32_t fpga_compat_num = _iface->peek32(U2_REG_COMPAT_NUM_RB); -    if (fpga_compat_num != USRP2_FPGA_COMPAT_NUM){ -        throw uhd::runtime_error(str(boost::format( -            "\nPlease update the firmware and FPGA images for your device.\n" -            "See the application notes for USRP2/N-Series for instructions.\n" -            "Expected FPGA compatibility number %d, but got %d:\n" -            "The FPGA build is not compatible with the host code build." -        ) % int(USRP2_FPGA_COMPAT_NUM) % fpga_compat_num)); -    } - -    //lock the device/motherboard to this process -    _iface->lock_device(true); - -    //construct transports for dsp and async errors -    UHD_LOG << "Making transport for DSP0..." << std::endl; -    device.dsp_xports.push_back(udp_zero_copy::make( -        device_addr["addr"], BOOST_STRINGIZE(USRP2_UDP_DSP0_PORT), device_addr -    )); -    init_xport(device.dsp_xports.back()); - -    UHD_LOG << "Making transport for DSP1..." << std::endl; -    device.dsp_xports.push_back(udp_zero_copy::make( -        device_addr["addr"], BOOST_STRINGIZE(USRP2_UDP_DSP1_PORT), device_addr -    )); -    init_xport(device.dsp_xports.back()); - -    UHD_LOG << "Making transport for ERR0..." << std::endl; -    device.err_xports.push_back(udp_zero_copy::make( -        device_addr["addr"], BOOST_STRINGIZE(USRP2_UDP_ERR0_PORT), device_addr_t() -    )); -    init_xport(device.err_xports.back()); - -    //contruct the interfaces to mboard perifs -    _clock_ctrl = usrp2_clock_ctrl::make(_iface); -    _codec_ctrl = usrp2_codec_ctrl::make(_iface); -    if (_iface->mb_eeprom["gpsdo"] == "internal"){ -        _gps_ctrl = gps_ctrl::make( -            _iface->get_gps_write_fn(), -            _iface->get_gps_read_fn()); -    } - -    //init the dsp stuff (before setting update packets) -    dsp_init(); - -    //setting the cycles per update (disabled by default) -    const double ups_per_sec = device_addr.cast<double>("ups_per_sec", 20); -    if (ups_per_sec > 0.0){ -        const size_t cycles_per_up = size_t(_clock_ctrl->get_master_clock_rate()/ups_per_sec); -        _iface->poke32(U2_REG_TX_CTRL_CYCLES_PER_UP, U2_FLAG_TX_CTRL_UP_ENB | cycles_per_up); -    } - -    //setting the packets per update (enabled by default) -    size_t send_frame_size = device.dsp_xports[0]->get_send_frame_size(); -    const double ups_per_fifo = device_addr.cast<double>("ups_per_fifo", 8.0); -    if (ups_per_fifo > 0.0){ -        const size_t packets_per_up = size_t(usrp2_impl::sram_bytes/ups_per_fifo/send_frame_size); -        _iface->poke32(U2_REG_TX_CTRL_PACKETS_PER_UP, U2_FLAG_TX_CTRL_UP_ENB | packets_per_up); -    } - -    //initialize the clock configuration -    if (device_addr.has_key("mimo_mode")){ -        if (device_addr["mimo_mode"] == "master"){ -            _mimo_clocking_mode_is_master = true; -        } -        else if (device_addr["mimo_mode"] == "slave"){ -            _mimo_clocking_mode_is_master = false; -        } -        else throw uhd::value_error( -            "mimo_mode must be set to master or slave" -        ); -    } -    else { -        _mimo_clocking_mode_is_master = (_iface->peek32(U2_REG_STATUS) & (1 << 8)) != 0; -    } -    UHD_MSG(status) << boost::format("mboard%d is MIMO %s") % _index % -        (_mimo_clocking_mode_is_master?"master":"slave") << std::endl; - -    //init the clock config -    if(_iface->mb_eeprom["gpsdo"] == "internal" or -       _iface->mb_eeprom["gpsdo"] == "external") { -        _clock_config = clock_config_t::external(); -    } -    else { -        _clock_config = clock_config_t::internal(); -    } -    update_clock_config(); - -    //init the codec before the dboard -    codec_init(); - -    //init the tx and rx dboards (do last) -    dboard_init(); - -    //set default subdev specs -    (*this)[MBOARD_PROP_RX_SUBDEV_SPEC] = subdev_spec_t(); -    (*this)[MBOARD_PROP_TX_SUBDEV_SPEC] = subdev_spec_t(); - -    //------------------------------------------------------------------ -    //This is a hack/fix for the lingering packet problem. -    stream_cmd_t stream_cmd(stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_DONE); -    for (size_t i = 0; i < NUM_RX_DSPS; i++){ -        size_t index = device.dsp_xports.size() - NUM_RX_DSPS + i; -        stream_cmd.num_samps = 1; -        this->issue_ddc_stream_cmd(stream_cmd, i); -        device.dsp_xports.at(index)->get_recv_buff(0.01).get(); //recv with timeout for lingering -        device.dsp_xports.at(index)->get_recv_buff(0.01).get(); //recv with timeout for expected -        _iface->poke32(U2_REG_RX_CTRL_CLEAR(i), 1); //resets sequence -    } -    //------------------------------------------------------------------ - -    //initialize VITA time to GPS time -    if( _gps_ctrl.get() -    and _gps_ctrl->gps_detected()) { -        UHD_MSG(status) << "Setting device time to GPS time...\n"; -        set_time_spec(time_spec_t(double(_gps_ctrl->get_sensor("gps_time").to_int()+1)), false); -    } -} - -usrp2_mboard_impl::~usrp2_mboard_impl(void){UHD_SAFE_CALL( -    _iface->poke32(U2_REG_TX_CTRL_CYCLES_PER_UP, 0); -    _iface->poke32(U2_REG_TX_CTRL_PACKETS_PER_UP, 0); -)} - -/*********************************************************************** - * Helper Methods - **********************************************************************/ -void usrp2_mboard_impl::update_clock_config(void){ -    boost::uint32_t pps_flags = 0; - -    //slave mode overrides clock config settings -    if (not _mimo_clocking_mode_is_master){ -        _clock_config.ref_source = clock_config_t::REF_MIMO; -        _clock_config.pps_source = clock_config_t::PPS_MIMO; -    } - -    //translate pps source enums -    switch(_clock_config.pps_source){ -    case clock_config_t::PPS_MIMO: -        _iface->poke32(U2_REG_TIME64_MIMO_SYNC, -            (1 << 8) | (mimo_clock_sync_delay_cycles & 0xff) -        ); -        break; - -    case clock_config_t::PPS_SMA: -        _iface->poke32(U2_REG_TIME64_MIMO_SYNC, 0); -        pps_flags |= U2_FLAG_TIME64_PPS_SMA; -        break; - -    default: throw uhd::value_error("unhandled clock configuration pps source"); -    } - -    //translate pps polarity enums -    switch(_clock_config.pps_polarity){ -    case clock_config_t::PPS_POS: pps_flags |= U2_FLAG_TIME64_PPS_POSEDGE; break; -    case clock_config_t::PPS_NEG: pps_flags |= U2_FLAG_TIME64_PPS_NEGEDGE; break; -    default: throw uhd::value_error("unhandled clock configuration pps polarity"); -    } - -    //set the pps flags -    _iface->poke32(U2_REG_TIME64_FLAGS, pps_flags); - -    //clock source ref 10mhz -    switch(_iface->get_rev()){ -    case usrp2_iface::USRP_N200: -    case usrp2_iface::USRP_N210: -    case usrp2_iface::USRP_N200_R4: -    case usrp2_iface::USRP_N210_R4: -        switch(_clock_config.ref_source){ -        case clock_config_t::REF_INT : _iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x12); break; -        case clock_config_t::REF_SMA : _iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x1C); break; -        case clock_config_t::REF_MIMO: _iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x15); break; -        default: throw uhd::value_error("unhandled clock configuration reference source"); -        } -        _clock_ctrl->enable_external_ref(true); //USRP2P has an internal 10MHz TCXO -        break; - -    case usrp2_iface::USRP2_REV3: -    case usrp2_iface::USRP2_REV4: -        switch(_clock_config.ref_source){ -        case clock_config_t::REF_INT : _iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x10); break; -        case clock_config_t::REF_SMA : _iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x1C); break; -        case clock_config_t::REF_MIMO: _iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x15); break; -        default: throw uhd::value_error("unhandled clock configuration reference source"); -        } -        _clock_ctrl->enable_external_ref(_clock_config.ref_source != clock_config_t::REF_INT); -        break; - -    case usrp2_iface::USRP_NXXX: break; -    } - -    //masters always drive the clock over serdes -    _clock_ctrl->enable_mimo_clock_out(_mimo_clocking_mode_is_master); - -    //set the mimo clock delay over the serdes -    if (_mimo_clocking_mode_is_master){ -        switch(_iface->get_rev()){ -        case usrp2_iface::USRP_N200: -        case usrp2_iface::USRP_N210: -        case usrp2_iface::USRP_N200_R4: -        case usrp2_iface::USRP_N210_R4: -            _clock_ctrl->set_mimo_clock_delay(mimo_clock_delay_usrp_n2xx); -            break; - -        case usrp2_iface::USRP2_REV4: -            _clock_ctrl->set_mimo_clock_delay(mimo_clock_delay_usrp2_rev4); -            break; - -        default: break; //not handled -        } -    } - -} - -void usrp2_mboard_impl::set_time_spec(const time_spec_t &time_spec, bool now){ -    //dont set the time for slave devices, they always take from mimo cable -    if (not _mimo_clocking_mode_is_master) return; - -    //set the ticks -    _iface->poke32(U2_REG_TIME64_TICKS, time_spec.get_tick_count(get_master_clock_freq())); - -    //set the flags register -    boost::uint32_t imm_flags = (now)? U2_FLAG_TIME64_LATCH_NOW : U2_FLAG_TIME64_LATCH_NEXT_PPS; -    _iface->poke32(U2_REG_TIME64_IMM, imm_flags); - -    //set the seconds (latches in all 3 registers) -    _iface->poke32(U2_REG_TIME64_SECS, boost::uint32_t(time_spec.get_full_secs())); -} - -/*********************************************************************** - * MBoard Get Properties - **********************************************************************/ -void usrp2_mboard_impl::get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); -    static const std::string dboard_name = "A"; - -    //handle the get request conditioned on the key -    switch(key.as<mboard_prop_t>()){ -    case MBOARD_PROP_NAME: -        val = _iface->get_cname() + " mboard"; -        return; - -    case MBOARD_PROP_OTHERS: -        val = prop_names_t(); -        return; - -    case MBOARD_PROP_RX_DBOARD: -        UHD_ASSERT_THROW(key.name == dboard_name or key.name == "0"); //allow for old name to work -        val = _rx_dboard_proxy->get_link(); -        return; - -    case MBOARD_PROP_RX_DBOARD_NAMES: -        val = prop_names_t(1, dboard_name); -        return; - -    case MBOARD_PROP_TX_DBOARD: -        UHD_ASSERT_THROW(key.name == dboard_name or key.name == "0"); //allow for old name to work -        val = _tx_dboard_proxy->get_link(); -        return; - -    case MBOARD_PROP_TX_DBOARD_NAMES: -        val = prop_names_t(1, dboard_name); -        return; - -    case MBOARD_PROP_RX_DSP: -        val = _rx_dsp_proxies[key.name]->get_link(); -        return; - -    case MBOARD_PROP_RX_DSP_NAMES: -        val = _rx_dsp_proxies.keys(); -        return; - -    case MBOARD_PROP_TX_DSP: -        val = _tx_dsp_proxies[key.name]->get_link(); -        return; - -    case MBOARD_PROP_TX_DSP_NAMES: -        val = _tx_dsp_proxies.keys(); -        return; - -    case MBOARD_PROP_CLOCK_CONFIG: -        val = _clock_config; -        return; - -    case MBOARD_PROP_TIME_NOW: while(true){ -        uint32_t secs = _iface->peek32(U2_REG_TIME64_SECS_RB_IMM); -        uint32_t ticks = _iface->peek32(U2_REG_TIME64_TICKS_RB_IMM); -        if (secs != _iface->peek32(U2_REG_TIME64_SECS_RB_IMM)) continue; -        val = time_spec_t(secs, ticks, get_master_clock_freq()); -        return; -    } - -    case MBOARD_PROP_TIME_PPS: while(true){ -        uint32_t secs = _iface->peek32(U2_REG_TIME64_SECS_RB_PPS); -        uint32_t ticks = _iface->peek32(U2_REG_TIME64_TICKS_RB_PPS); -        if (secs != _iface->peek32(U2_REG_TIME64_SECS_RB_PPS)) continue; -        val = time_spec_t(secs, ticks, get_master_clock_freq()); -        return; -    } - -    case MBOARD_PROP_RX_SUBDEV_SPEC: -        val = _rx_subdev_spec; -        return; - -    case MBOARD_PROP_TX_SUBDEV_SPEC: -        val = _tx_subdev_spec; -        return; - -    case MBOARD_PROP_EEPROM_MAP: -        val = _iface->mb_eeprom; -        return; - -    case MBOARD_PROP_CLOCK_RATE: -        val = this->get_master_clock_freq(); -        return; - -    case SUBDEV_PROP_SENSOR_NAMES:{ -            prop_names_t names = boost::assign::list_of("mimo_locked")("ref_locked"); -            if (_gps_ctrl.get()) { -                std::vector<std::string> gs = _gps_ctrl->get_sensors(); -                names.insert(names.end(), gs.begin(), gs.end()); -            } -            val = names; -        } -        return; - -    case MBOARD_PROP_SENSOR: -        if(key.name == "mimo_locked") { -            val = sensor_value_t("MIMO", this->get_mimo_locked(), "locked", "unlocked"); -            return; -        } -        else if(key.name == "ref_locked") { -            val = sensor_value_t("Ref", this->get_ref_locked(), "locked", "unlocked"); -            return; -        } -        else if(uhd::has(_gps_ctrl->get_sensors(), key.name) and _gps_ctrl.get()) { -            val = _gps_ctrl->get_sensor(key.name); -        } -        else { -            UHD_THROW_PROP_GET_ERROR(); -        } -        break; - -    default: UHD_THROW_PROP_GET_ERROR(); -    } -} - -bool usrp2_mboard_impl::get_mimo_locked(void) { -  return bool((_iface->peek32(U2_REG_IRQ_RB) & (1<<10)) > 0); -} - -bool usrp2_mboard_impl::get_ref_locked(void) { -  return bool((_iface->peek32(U2_REG_IRQ_RB) & (1<<11)) > 0); -} - -/*********************************************************************** - * MBoard Set Properties - **********************************************************************/ -void usrp2_mboard_impl::set(const wax::obj &key, const wax::obj &val){ -    //handle the set request conditioned on the key -    switch(key.as<mboard_prop_t>()){ - -    case MBOARD_PROP_CLOCK_CONFIG: -        _clock_config = val.as<clock_config_t>(); -        update_clock_config(); -        return; - -    case MBOARD_PROP_TIME_NOW: -        set_time_spec(val.as<time_spec_t>(), true); -        return; - -    case MBOARD_PROP_TIME_PPS: -        set_time_spec(val.as<time_spec_t>(), false); -        return; - -    case MBOARD_PROP_RX_SUBDEV_SPEC:{ -        _rx_subdev_spec = val.as<subdev_spec_t>(); -        verify_rx_subdev_spec(_rx_subdev_spec, this->get_link()); -        //sanity check -        UHD_ASSERT_THROW(_rx_subdev_spec.size() <= NUM_RX_DSPS); - -        //determine frontend swap IQ from the first channel -        bool fe_swap_iq = false; -        switch(_dboard_manager->get_rx_subdev(_rx_subdev_spec.at(0).sd_name)[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>()){ -        case SUBDEV_CONN_COMPLEX_QI: -        case SUBDEV_CONN_REAL_Q: -            fe_swap_iq = true; -            break; -        default: fe_swap_iq = false; -        } -        _iface->poke32(U2_REG_RX_FE_SWAP_IQ, fe_swap_iq? 1 : 0); - -        //set the dsp mux for each channel -        for (size_t i = 0; i < _rx_subdev_spec.size(); i++){ -            bool iq_swap = false, real_mode = false; -            switch(_dboard_manager->get_rx_subdev(_rx_subdev_spec.at(i).sd_name)[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>()){ -            case SUBDEV_CONN_COMPLEX_IQ: -                iq_swap = fe_swap_iq; -                real_mode = false; -                break; -            case SUBDEV_CONN_COMPLEX_QI: -                iq_swap = not fe_swap_iq; -                real_mode = false; -                break; -            case SUBDEV_CONN_REAL_I: -                iq_swap = fe_swap_iq; -                real_mode = true; -                break; -            case SUBDEV_CONN_REAL_Q: -                iq_swap = not fe_swap_iq; -                real_mode = true; -                break; -            } -            _iface->poke32(U2_REG_DSP_RX_MUX(i), -                (iq_swap?   U2_FLAG_DSP_RX_MUX_SWAP_IQ   : 0) | -                (real_mode? U2_FLAG_DSP_RX_MUX_REAL_MODE : 0) -            ); -        } -        _device.update_xport_channel_mapping(); -    }return; - -    case MBOARD_PROP_TX_SUBDEV_SPEC: -        _tx_subdev_spec = val.as<subdev_spec_t>(); -        verify_tx_subdev_spec(_tx_subdev_spec, this->get_link()); -        //sanity check -        UHD_ASSERT_THROW(_tx_subdev_spec.size() <= NUM_TX_DSPS); -        //set the mux -        for (size_t i = 0; i < _rx_subdev_spec.size(); i++){ -            _iface->poke32(U2_REG_TX_FE_MUX, dsp_type1::calc_tx_mux_word( -                _dboard_manager->get_tx_subdev(_tx_subdev_spec[i].sd_name)[SUBDEV_PROP_CONNECTION].as<subdev_conn_t>() -            )); -        } -        _device.update_xport_channel_mapping(); -        return; - -    case MBOARD_PROP_EEPROM_MAP: -        // Step1: commit the map, writing only those values set. -        // Step2: readback the entire eeprom map into the iface. -        val.as<mboard_eeprom_t>().commit(*_iface, mboard_eeprom_t::MAP_N100); -        _iface->mb_eeprom = mboard_eeprom_t(*_iface, mboard_eeprom_t::MAP_N100); -        return; - -    case MBOARD_PROP_CLOCK_RATE: -        UHD_ASSERT_THROW(val.as<double>() == this->get_master_clock_freq()); -        _device.update_xport_channel_mapping(); -        return; - -    default: UHD_THROW_PROP_SET_ERROR(); -    } -} diff --git a/host/lib/usrp/usrp2/usrp2_iface.cpp b/host/lib/usrp/usrp2/usrp2_iface.cpp index 6ba364b28..0db9e5d58 100644 --- a/host/lib/usrp/usrp2/usrp2_iface.cpp +++ b/host/lib/usrp/usrp2/usrp2_iface.cpp @@ -160,24 +160,24 @@ public:  /***********************************************************************   * Peek and Poke   **********************************************************************/ -    void poke32(boost::uint32_t addr, boost::uint32_t data){ +    void poke32(wb_addr_type addr, boost::uint32_t data){          this->get_reg<boost::uint32_t, USRP2_REG_ACTION_FPGA_POKE32>(addr, data);      } -    boost::uint32_t peek32(boost::uint32_t addr){ +    boost::uint32_t peek32(wb_addr_type addr){          return this->get_reg<boost::uint32_t, USRP2_REG_ACTION_FPGA_PEEK32>(addr);      } -    void poke16(boost::uint32_t addr, boost::uint16_t data){ +    void poke16(wb_addr_type addr, boost::uint16_t data){          this->get_reg<boost::uint16_t, USRP2_REG_ACTION_FPGA_POKE16>(addr, data);      } -    boost::uint16_t peek16(boost::uint32_t addr){ +    boost::uint16_t peek16(wb_addr_type addr){          return this->get_reg<boost::uint16_t, USRP2_REG_ACTION_FPGA_PEEK16>(addr);      }      template <class T, usrp2_reg_action_t action> -    T get_reg(boost::uint32_t addr, T data = 0){ +    T get_reg(wb_addr_type addr, T data = 0){          //setup the out data          usrp2_ctrl_data_t out_data = usrp2_ctrl_data_t();          out_data.id = htonl(USRP2_CTRL_ID_GET_THIS_REGISTER_FOR_ME_BRO); diff --git a/host/lib/usrp/usrp2/usrp2_iface.hpp b/host/lib/usrp/usrp2/usrp2_iface.hpp index 16b640a70..f36febce4 100644 --- a/host/lib/usrp/usrp2/usrp2_iface.hpp +++ b/host/lib/usrp/usrp2/usrp2_iface.hpp @@ -19,15 +19,14 @@  #define INCLUDED_USRP2_IFACE_HPP  #include <uhd/transport/udp_simple.hpp> -#include <uhd/usrp/mboard_iface.hpp> +#include <uhd/types/serial.hpp> +#include <uhd/usrp/mboard_eeprom.hpp>  #include <boost/shared_ptr.hpp>  #include <boost/utility.hpp> -#include <boost/cstdint.hpp>  #include <boost/function.hpp> -#include <utility> -#include <string>  #include "usrp2_regs.hpp" - +#include "wb_iface.hpp" +#include <string>  //TODO: kill this crap when you have the top level GPS include file  typedef boost::function<void(std::string)> gps_send_fn_t; @@ -38,7 +37,7 @@ typedef boost::function<std::string(void)> gps_recv_fn_t;   * Provides a set of functions to implementation layer.   * Including spi, peek, poke, control...   */ -class usrp2_iface : public uhd::usrp::mboard_iface, boost::noncopyable{ +class usrp2_iface : public wb_iface, public uhd::spi_iface, public uhd::i2c_iface, public uhd::uart_iface{  public:      typedef boost::shared_ptr<usrp2_iface> sptr;      /*! diff --git a/host/lib/usrp/usrp2/usrp2_impl.cpp b/host/lib/usrp/usrp2/usrp2_impl.cpp index aa584ac8b..390d1813b 100644 --- a/host/lib/usrp/usrp2/usrp2_impl.cpp +++ b/host/lib/usrp/usrp2/usrp2_impl.cpp @@ -22,18 +22,18 @@  #include <uhd/exception.hpp>  #include <uhd/transport/if_addrs.hpp>  #include <uhd/transport/udp_zero_copy.hpp> -#include <uhd/usrp/device_props.hpp> +#include <uhd/types/ranges.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/static.hpp>  #include <uhd/utils/byteswap.hpp> -#include <boost/assign/list_of.hpp> +#include <uhd/utils/safe_call.hpp>  #include <boost/format.hpp>  #include <boost/foreach.hpp>  #include <boost/lexical_cast.hpp>  #include <boost/bind.hpp> +#include <boost/assign/list_of.hpp>  #include <boost/asio/ip/address_v4.hpp>  #include <boost/asio.hpp> //used for htonl and ntohl -#include <vector>  using namespace uhd;  using namespace uhd::usrp; @@ -227,6 +227,23 @@ static mtu_result_t determine_mtu(const std::string &addr, const mtu_result_t &u  }  /*********************************************************************** + * Helpers + **********************************************************************/ +static void init_xport(zero_copy_if::sptr xport){ +    //Send a small data packet so the usrp2 knows the udp source port. +    //This setup must happen before further initialization occurs +    //or the async update packets will cause ICMP destination unreachable. +    static const boost::uint32_t data[2] = { +        uhd::htonx(boost::uint32_t(0 /* don't care seq num */)), +        uhd::htonx(boost::uint32_t(USRP2_INVALID_VRT_HEADER)) +    }; + +    transport::managed_send_buffer::sptr send_buff = xport->get_send_buff(); +    std::memcpy(send_buff->cast<void*>(), &data, sizeof(data)); +    send_buff->commit(sizeof(data)); +} + +/***********************************************************************   * Structors   **********************************************************************/  usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){ @@ -272,67 +289,407 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){      device_args = separate_device_addr(device_addr); //update args for new frame sizes -    //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; +    //////////////////////////////////////////////////////////////////// +    // create controller objects and initialize the properties tree +    //////////////////////////////////////////////////////////////////// +    _tree = property_tree::make(); +    _tree->create<std::string>("/name").set("USRP2 / N-Series Device"); + +    for (size_t mbi = 0; mbi < device_args.size(); mbi++){ +        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"]; +        const property_tree::path_type mb_path = "/mboards/" + mb; + +        //////////////////////////////////////////////////////////////// +        // construct transports for dsp and async errors +        //////////////////////////////////////////////////////////////// +        UHD_LOG << "Making transport for DSP0..." << std::endl; +        _mbc[mb].dsp_xports.push_back(udp_zero_copy::make( +            addr, BOOST_STRINGIZE(USRP2_UDP_DSP0_PORT), device_args_i +        )); +        init_xport(_mbc[mb].dsp_xports.back()); -    //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; +        UHD_LOG << "Making transport for DSP1..." << std::endl; +        _mbc[mb].dsp_xports.push_back(udp_zero_copy::make( +            addr, BOOST_STRINGIZE(USRP2_UDP_DSP1_PORT), device_args_i +        )); +        init_xport(_mbc[mb].dsp_xports.back()); -    //!!!!! set the otw type here before continuing, its used below +        UHD_LOG << "Making transport for ERR0..." << std::endl; +        _mbc[mb].err_xports.push_back(udp_zero_copy::make( +            addr, BOOST_STRINGIZE(USRP2_UDP_ERR0_PORT), device_addr_t() +        )); +        init_xport(_mbc[mb].err_xports.back()); -    //create a new mboard handler for each control transport -    for(size_t i = 0; i < device_args.size(); i++){ -        device_addr_t dev_addr_i = device_args[i]; -        BOOST_FOREACH(const std::string &key, device_addr.keys()){ -            if (dev_addr_i.has_key(key)) continue; -            dev_addr_i[key] = device_addr[key]; +        //////////////////////////////////////////////////////////////// +        // create the iface that controls i2c, spi, uart, and wb +        //////////////////////////////////////////////////////////////// +        _mbc[mb].iface = usrp2_iface::make(udp_simple::make_connected( +            addr, BOOST_STRINGIZE(USRP2_UDP_CTRL_PORT) +        )); +        _tree->create<std::string>(mb_path / "name").set(_mbc[mb].iface->get_cname()); + +        //check the fpga compatibility number +        const boost::uint32_t fpga_compat_num = _mbc[mb].iface->peek32(U2_REG_COMPAT_NUM_RB); +        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; +            fpga_minor = 0; +        } +        if (fpga_major != USRP2_FPGA_COMPAT_NUM){ +            throw uhd::runtime_error(str(boost::format( +                "\nPlease update the firmware and FPGA images for your device.\n" +                "See the application notes for USRP2/N-Series for instructions.\n" +                "Expected FPGA compatibility number %d, but got %d:\n" +                "The FPGA build is not compatible with the host code build." +            ) % int(USRP2_FPGA_COMPAT_NUM) % fpga_major)); +        } +        _tree->create<std::string>(mb_path / "fpga_version").set(str(boost::format("%u.%u") % fpga_major % fpga_minor)); + +        //lock the device/motherboard to this process +        _mbc[mb].iface->lock_device(true); + +        //////////////////////////////////////////////////////////////// +        // setup the mboard eeprom +        //////////////////////////////////////////////////////////////// +        _tree->create<mboard_eeprom_t>(mb_path / "eeprom") +            .set(_mbc[mb].iface->mb_eeprom) +            .subscribe(boost::bind(&usrp2_impl::set_mb_eeprom, this, mb, _1)); + +        //////////////////////////////////////////////////////////////// +        // create clock control objects +        //////////////////////////////////////////////////////////////// +        _mbc[mb].clock = usrp2_clock_ctrl::make(_mbc[mb].iface); +        _tree->create<double>(mb_path / "tick_rate") +            .publish(boost::bind(&usrp2_clock_ctrl::get_master_clock_rate, _mbc[mb].clock)) +            .subscribe(boost::bind(&usrp2_impl::update_tick_rate, this, _1)); + +        //////////////////////////////////////////////////////////////// +        // create codec control objects +        //////////////////////////////////////////////////////////////// +        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); +        switch(_mbc[mb].iface->get_rev()){ +        case usrp2_iface::USRP_N200: +        case usrp2_iface::USRP_N210: +        case usrp2_iface::USRP_N200_R4: +        case usrp2_iface::USRP_N210_R4:{ +            _tree->create<std::string>(rx_codec_path / "name").set("ads62p44"); +            _tree->create<meta_range_t>(rx_codec_path / "gains/digital/range").set(meta_range_t(0, 6.0, 0.5)); +            _tree->create<double>(rx_codec_path / "gains/digital/value") +                .subscribe(boost::bind(&usrp2_codec_ctrl::set_rx_digital_gain, _mbc[mb].codec, _1)).set(0); +            _tree->create<meta_range_t>(rx_codec_path / "gains/fine/range").set(meta_range_t(0, 0.5, 0.05)); +            _tree->create<double>(rx_codec_path / "gains/fine/value") +                .subscribe(boost::bind(&usrp2_codec_ctrl::set_rx_digital_fine_gain, _mbc[mb].codec, _1)).set(0); +        }break; + +        case usrp2_iface::USRP2_REV3: +        case usrp2_iface::USRP2_REV4: +            _tree->create<std::string>(rx_codec_path / "name").set("ltc2284"); +            break; + +        case usrp2_iface::USRP_NXXX: +            _tree->create<std::string>(rx_codec_path / "name").set("??????"); +            break; +        } +        _tree->create<std::string>(tx_codec_path / "name").set("ad9777"); + +        //////////////////////////////////////////////////////////////// +        // create gpsdo control objects +        //////////////////////////////////////////////////////////////// +        if (_mbc[mb].iface->mb_eeprom["gpsdo"] == "internal"){ +            _mbc[mb].gps = gps_ctrl::make( +                _mbc[mb].iface->get_gps_write_fn(), +                _mbc[mb].iface->get_gps_read_fn() +            ); +            BOOST_FOREACH(const std::string &name, _mbc[mb].gps->get_sensors()){ +                _tree->create<sensor_value_t>(mb_path / "sensors" / name) +                    .publish(boost::bind(&gps_ctrl::get_sensor, _mbc[mb].gps, name)); +            }          } -        _mboards.push_back(usrp2_mboard_impl::sptr( -            new usrp2_mboard_impl(dev_addr_i, i, *this) + +        //////////////////////////////////////////////////////////////// +        // and do the misc mboard sensors +        //////////////////////////////////////////////////////////////// +        _tree->create<sensor_value_t>(mb_path / "sensors/mimo_locked") +            .publish(boost::bind(&usrp2_impl::get_mimo_locked, this, mb)); +        _tree->create<sensor_value_t>(mb_path / "sensors/ref_locked") +            .publish(boost::bind(&usrp2_impl::get_ref_locked, this, mb)); + +        //////////////////////////////////////////////////////////////// +        // create frontend control objects +        //////////////////////////////////////////////////////////////// +        _mbc[mb].rx_fe = rx_frontend_core_200::make( +            _mbc[mb].iface, U2_REG_SR_ADDR(SR_RX_FRONT) +        ); +        _mbc[mb].tx_fe = tx_frontend_core_200::make( +            _mbc[mb].iface, U2_REG_SR_ADDR(SR_TX_FRONT) +        ); +        //TODO lots of properties to expose here for frontends +        _tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec") +            .coerce(boost::bind(&usrp2_impl::update_rx_subdev_spec, this, mb, _1)); +        _tree->create<subdev_spec_t>(mb_path / "tx_subdev_spec") +            .coerce(boost::bind(&usrp2_impl::update_tx_subdev_spec, this, mb, _1)); + +        //////////////////////////////////////////////////////////////// +        // create rx dsp control objects +        //////////////////////////////////////////////////////////////// +        _mbc[mb].rx_dsps.push_back(rx_dsp_core_200::make( +            _mbc[mb].iface, U2_REG_SR_ADDR(SR_RX_DSP0), U2_REG_SR_ADDR(SR_RX_CTRL0), USRP2_RX_SID_BASE + 0, true +        )); +        _mbc[mb].rx_dsps.push_back(rx_dsp_core_200::make( +            _mbc[mb].iface, U2_REG_SR_ADDR(SR_RX_DSP1), U2_REG_SR_ADDR(SR_RX_CTRL1), USRP2_RX_SID_BASE + 1, true          )); -        //use an empty name when there is only one mboard -        std::string name = (device_args.size() > 1)? boost::lexical_cast<std::string>(i) : ""; -        _mboard_dict[name] = _mboards.back(); +        for (size_t dspno = 0; dspno < _mbc[mb].rx_dsps.size(); dspno++){ +            _mbc[mb].rx_dsps[dspno]->set_link_rate(USRP2_LINK_RATE_BPS); +            _tree->access<double>(mb_path / "tick_rate") +                .subscribe(boost::bind(&rx_dsp_core_200::set_tick_rate, _mbc[mb].rx_dsps[dspno], _1)); +            //This is a hack/fix for the lingering packet problem. +            //The dsp core starts streaming briefly... now we flush +            _mbc[mb].dsp_xports[dspno]->get_recv_buff(0.01).get(); //recv with timeout for lingering +            _mbc[mb].dsp_xports[dspno]->get_recv_buff(0.01).get(); //recv with timeout for expected +            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, _mbc[mb].rx_dsps[dspno], _1)) +                .subscribe(boost::bind(&usrp2_impl::update_rx_samp_rate, this, _1)); +            _tree->create<double>(rx_dsp_path / "freq/value") +                .coerce(boost::bind(&rx_dsp_core_200::set_freq, _mbc[mb].rx_dsps[dspno], _1)); +            _tree->create<meta_range_t>(rx_dsp_path / "freq/range") +                .publish(boost::bind(&rx_dsp_core_200::get_freq_range, _mbc[mb].rx_dsps[dspno])); +            _tree->create<stream_cmd_t>(rx_dsp_path / "stream_cmd") +                .subscribe(boost::bind(&rx_dsp_core_200::issue_stream_command, _mbc[mb].rx_dsps[dspno], _1)); +        } + +        //////////////////////////////////////////////////////////////// +        // create tx dsp control objects +        //////////////////////////////////////////////////////////////// +        _mbc[mb].tx_dsp = tx_dsp_core_200::make( +            _mbc[mb].iface, U2_REG_SR_ADDR(SR_TX_DSP), U2_REG_SR_ADDR(SR_TX_CTRL), USRP2_TX_ASYNC_SID +        ); +        _mbc[mb].tx_dsp->set_link_rate(USRP2_LINK_RATE_BPS); +        _tree->access<double>(mb_path / "tick_rate") +            .subscribe(boost::bind(&tx_dsp_core_200::set_tick_rate, _mbc[mb].tx_dsp, _1)); +        _tree->create<double>(mb_path / "tx_dsps/0/rate/value") +            .coerce(boost::bind(&tx_dsp_core_200::set_host_rate, _mbc[mb].tx_dsp, _1)) +            .subscribe(boost::bind(&usrp2_impl::update_tx_samp_rate, this, _1)); +        _tree->create<double>(mb_path / "tx_dsps/0/freq/value") +            .coerce(boost::bind(&usrp2_impl::set_tx_dsp_freq, this, mb, _1)); +        _tree->create<meta_range_t>(mb_path / "tx_dsps/0/freq/range") +            .publish(boost::bind(&usrp2_impl::get_tx_dsp_freq_range, this, mb)); + +        //setup dsp flow control +        const double ups_per_sec = device_args_i.cast<double>("ups_per_sec", 20); +        const size_t send_frame_size = _mbc[mb].dsp_xports.front()->get_send_frame_size(); +        const double ups_per_fifo = device_args_i.cast<double>("ups_per_fifo", 8.0); +        _mbc[mb].tx_dsp->set_updates( +            (ups_per_sec > 0.0)? size_t(100e6/*approx tick rate*//ups_per_sec) : 0, +            (ups_per_fifo > 0.0)? size_t(USRP2_SRAM_BYTES/ups_per_fifo/send_frame_size) : 0 +        ); + +        //////////////////////////////////////////////////////////////// +        // create time control objects +        //////////////////////////////////////////////////////////////// +        time64_core_200::readback_bases_type time64_rb_bases; +        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( +            _mbc[mb].iface, U2_REG_SR_ADDR(SR_TIME64), time64_rb_bases, mimo_clock_sync_delay_cycles +        ); +        _tree->access<double>(mb_path / "tick_rate") +            .subscribe(boost::bind(&time64_core_200::set_tick_rate, _mbc[mb].time64, _1)); +        _tree->create<time_spec_t>(mb_path / "time/now") +            .publish(boost::bind(&time64_core_200::get_time_now, _mbc[mb].time64)) +            .subscribe(boost::bind(&time64_core_200::set_time_now, _mbc[mb].time64, _1)); +        _tree->create<time_spec_t>(mb_path / "time/pps") +            .publish(boost::bind(&time64_core_200::get_time_last_pps, _mbc[mb].time64)) +            .subscribe(boost::bind(&time64_core_200::set_time_next_pps, _mbc[mb].time64, _1)); +        //setup time source props +        _tree->create<std::string>(mb_path / "time_source/value") +            .subscribe(boost::bind(&time64_core_200::set_time_source, _mbc[mb].time64, _1)); +        _tree->create<std::vector<std::string> >(mb_path / "time_source/options") +            .publish(boost::bind(&time64_core_200::get_time_sources, _mbc[mb].time64)); +        //setup reference source props +        _tree->create<std::string>(mb_path / "clock_source/value") +            .subscribe(boost::bind(&usrp2_impl::update_clock_source, this, mb, _1)); +        static const std::vector<std::string> clock_sources = boost::assign::list_of("internal")("external")("mimo"); +        _tree->create<std::vector<std::string> >(mb_path / "clock_source/options").set(clock_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(*_mbc[mb].iface, USRP2_I2C_ADDR_RX_DB); +        tx_db_eeprom.load(*_mbc[mb].iface, USRP2_I2C_ADDR_TX_DB); +        gdb_eeprom.load(*_mbc[mb].iface, USRP2_I2C_ADDR_TX_DB ^ 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(&usrp2_impl::set_db_eeprom, this, mb, "rx", _1)); +        _tree->create<dboard_eeprom_t>(mb_path / "dboards/A/tx_eeprom") +            .set(tx_db_eeprom) +            .subscribe(boost::bind(&usrp2_impl::set_db_eeprom, this, mb, "tx", _1)); +        _tree->create<dboard_eeprom_t>(mb_path / "dboards/A/gdb_eeprom") +            .set(gdb_eeprom) +            .subscribe(boost::bind(&usrp2_impl::set_db_eeprom, this, mb, "gdb", _1)); + +        //create a new dboard interface and manager +        _mbc[mb].dboard_iface = make_usrp2_dboard_iface(_mbc[mb].iface, _mbc[mb].clock); +        _tree->create<dboard_iface::sptr>(mb_path / "dboards/A/iface").set(_mbc[mb].dboard_iface); +        _mbc[mb].dboard_manager = dboard_manager::make( +            rx_db_eeprom.id, +            ((gdb_eeprom.id == dboard_id_t::none())? tx_db_eeprom : gdb_eeprom).id, +            _mbc[mb].dboard_iface +        ); +        BOOST_FOREACH(const std::string &name, _mbc[mb].dboard_manager->get_rx_subdev_names()){ +            dboard_manager::populate_prop_tree_from_subdev( +                _tree, mb_path / "dboards/A/rx_frontends" / name, +                _mbc[mb].dboard_manager->get_rx_subdev(name) +            ); +        } +        BOOST_FOREACH(const std::string &name, _mbc[mb].dboard_manager->get_tx_subdev_names()){ +            dboard_manager::populate_prop_tree_from_subdev( +                _tree, mb_path / "dboards/A/tx_frontends" / name, +                _mbc[mb].dboard_manager->get_tx_subdev(name) +            ); +        }      } -    //init the send and recv io -    io_init(); +    //initialize io handling +    this->io_init(); + +    //do some post-init tasks +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        property_tree::path_type root = "/mboards/" + mb; +        _tree->access<double>(root / "tick_rate").update(); + +        //and now that the tick rate is set, init the host rates to something +        BOOST_FOREACH(const std::string &name, _tree->list(root / "rx_dsps")){ +            _tree->access<double>(root / "rx_dsps" / name / "rate" / "value").set(1e6); +        } +        BOOST_FOREACH(const std::string &name, _tree->list(root / "tx_dsps")){ +            _tree->access<double>(root / "tx_dsps" / name / "rate" / "value").set(1e6); +        } + +        _tree->access<subdev_spec_t>(root / "rx_subdev_spec").set(subdev_spec_t("A:"+_mbc[mb].dboard_manager->get_rx_subdev_names()[0])); +        _tree->access<subdev_spec_t>(root / "tx_subdev_spec").set(subdev_spec_t("A:"+_mbc[mb].dboard_manager->get_tx_subdev_names()[0])); +        _tree->access<std::string>(root / "clock_source/value").set("internal"); +        _tree->access<std::string>(root / "time_source/value").set("none"); + +        //GPS installed: use external ref, time, and init time spec +        if (_mbc[mb].gps.get() != NULL){ +            _tree->access<std::string>(root / "time_source/value").set("external"); +            _tree->access<std::string>(root / "clock_source/value").set("external"); +            _mbc[mb].time64->set_time_next_pps(time_spec_t(time_t(_mbc[mb].gps->get_sensor("gps_time").to_int()+1))); +        } +    }  } -usrp2_impl::~usrp2_impl(void){ -    /* NOP */ +usrp2_impl::~usrp2_impl(void){UHD_SAFE_CALL( +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        _mbc[mb].tx_dsp->set_updates(0, 0); +    } +)} + +void usrp2_impl::set_mb_eeprom(const std::string &mb, const uhd::usrp::mboard_eeprom_t &mb_eeprom){ +    mb_eeprom.commit(*(_mbc[mb].iface), mboard_eeprom_t::MAP_N100);  } -/*********************************************************************** - * Device Properties - **********************************************************************/ -void usrp2_impl::get(const wax::obj &key_, wax::obj &val){ -    named_prop_t key = named_prop_t::extract(key_); +void usrp2_impl::set_db_eeprom(const std::string &mb, const std::string &type, const uhd::usrp::dboard_eeprom_t &db_eeprom){ +    if (type == "rx") db_eeprom.store(*_mbc[mb].iface, USRP2_I2C_ADDR_RX_DB); +    if (type == "tx") db_eeprom.store(*_mbc[mb].iface, USRP2_I2C_ADDR_TX_DB); +    if (type == "gdb") db_eeprom.store(*_mbc[mb].iface, USRP2_I2C_ADDR_TX_DB ^ 5); +} -    //handle the get request conditioned on the key -    switch(key.as<device_prop_t>()){ -    case DEVICE_PROP_NAME: -        if (_mboards.size() > 1) val = std::string("USRP2/N Series multi-device"); -        else                     val = std::string("USRP2/N Series device"); -        return; +sensor_value_t usrp2_impl::get_mimo_locked(const std::string &mb){ +    const bool lock = (_mbc[mb].iface->peek32(U2_REG_IRQ_RB) & (1<<10)) != 0; +    return sensor_value_t("MIMO", lock, "locked", "unlocked"); +} -    case DEVICE_PROP_MBOARD: -        val = _mboard_dict[key.name]->get_link(); -        return; +sensor_value_t usrp2_impl::get_ref_locked(const std::string &mb){ +    const bool lock = (_mbc[mb].iface->peek32(U2_REG_IRQ_RB) & (1<<11)) != 0; +    return sensor_value_t("Ref", lock, "locked", "unlocked"); +} -    case DEVICE_PROP_MBOARD_NAMES: -        val = prop_names_t(_mboard_dict.keys()); -        return; +#include <boost/math/special_functions/round.hpp> +#include <boost/math/special_functions/sign.hpp> -    default: UHD_THROW_PROP_GET_ERROR(); -    } +double usrp2_impl::set_tx_dsp_freq(const std::string &mb, const double freq_){ +    double new_freq = freq_; +    const double tick_rate = _tree->access<double>("/mboards/"+mb+"/tick_rate").get(); + +    //calculate the DAC shift (multiples of rate) +    const int sign = boost::math::sign(new_freq); +    const int zone = std::min(boost::math::iround(new_freq/tick_rate), 2); +    const double dac_shift = sign*zone*tick_rate; +    new_freq -= dac_shift; //update FPGA DSP target freq + +    //set the DAC shift (modulation mode) +    if (zone == 0) _mbc[mb].codec->set_tx_mod_mode(0); //no shift +    else _mbc[mb].codec->set_tx_mod_mode(sign*4/zone); //DAC interp = 4 + +    return _mbc[mb].tx_dsp->set_freq(new_freq) + dac_shift; //actual freq  } -void usrp2_impl::set(const wax::obj &, const wax::obj &){ -    UHD_THROW_PROP_SET_ERROR(); +meta_range_t usrp2_impl::get_tx_dsp_freq_range(const std::string &mb){ +    const double tick_rate = _tree->access<double>("/mboards/"+mb+"/tick_rate").get(); +    const meta_range_t dsp_range = _mbc[mb].tx_dsp->get_freq_range(); +    return meta_range_t(dsp_range.start() - tick_rate*2, dsp_range.stop() + tick_rate*2, dsp_range.step()); +} + +void usrp2_impl::update_clock_source(const std::string &mb, const std::string &source){ +    //clock source ref 10mhz +    switch(_mbc[mb].iface->get_rev()){ +    case usrp2_iface::USRP_N200: +    case usrp2_iface::USRP_N210: +    case usrp2_iface::USRP_N200_R4: +    case usrp2_iface::USRP_N210_R4: +        if (source == "internal")       _mbc[mb].iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x12); +        else if (source == "external")  _mbc[mb].iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x1C); +        else if (source == "mimo")      _mbc[mb].iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x15); +        else throw uhd::value_error("unhandled clock configuration reference source: " + source); +        _mbc[mb].clock->enable_external_ref(true); //USRP2P has an internal 10MHz TCXO +        break; + +    case usrp2_iface::USRP2_REV3: +    case usrp2_iface::USRP2_REV4: +        if (source == "internal")       _mbc[mb].iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x10); +        else if (source == "external")  _mbc[mb].iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x1C); +        else if (source == "mimo")      _mbc[mb].iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x15); +        else throw uhd::value_error("unhandled clock configuration reference source: " + source); +        _mbc[mb].clock->enable_external_ref(source != "internal"); +        break; + +    case usrp2_iface::USRP_NXXX: break; +    } + +    //always drive the clock over serdes if not locking to it +    _mbc[mb].clock->enable_mimo_clock_out(source != "mimo"); + +    //set the mimo clock delay over the serdes +    if (source != "mimo"){ +        switch(_mbc[mb].iface->get_rev()){ +        case usrp2_iface::USRP_N200: +        case usrp2_iface::USRP_N210: +        case usrp2_iface::USRP_N200_R4: +        case usrp2_iface::USRP_N210_R4: +            _mbc[mb].clock->set_mimo_clock_delay(mimo_clock_delay_usrp_n2xx); +            break; + +        case usrp2_iface::USRP2_REV4: +            _mbc[mb].clock->set_mimo_clock_delay(mimo_clock_delay_usrp2_rev4); +            break; + +        default: break; //not handled +        } +    }  } diff --git a/host/lib/usrp/usrp2/usrp2_impl.hpp b/host/lib/usrp/usrp2/usrp2_impl.hpp index 4d19863b1..f2125e094 100644 --- a/host/lib/usrp/usrp2/usrp2_impl.hpp +++ b/host/lib/usrp/usrp2/usrp2_impl.hpp @@ -21,6 +21,12 @@  #include "usrp2_iface.hpp"  #include "clock_ctrl.hpp"  #include "codec_ctrl.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/property_tree.hpp>  #include <uhd/usrp/gps_ctrl.hpp>  #include <uhd/device.hpp>  #include <uhd/utils/pimpl.hpp> @@ -37,6 +43,14 @@  #include <uhd/usrp/dboard_manager.hpp>  #include <uhd/usrp/subdev_spec.hpp> +static const double USRP2_LINK_RATE_BPS = 1000e6/8; +static const double mimo_clock_delay_usrp2_rev4 = 4.18e-9; +static const double mimo_clock_delay_usrp_n2xx = 3.55e-9; +static const size_t mimo_clock_sync_delay_cycles = 137; +static const size_t USRP2_SRAM_BYTES = size_t(1 << 20); +static const boost::uint32_t USRP2_TX_ASYNC_SID = 2; +static const boost::uint32_t USRP2_RX_SID_BASE = 3; +  /*!   * Make a usrp2 dboard interface.   * \param iface the usrp2 interface object @@ -49,139 +63,13 @@ uhd::usrp::dboard_iface::sptr make_usrp2_dboard_iface(  );  /*! - * 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);} -}; - -class usrp2_impl; - -/*! - * USRP2 mboard implementation guts: - * The implementation details are encapsulated here. - * Handles properties on the mboard, dboard, dsps... - */ -class usrp2_mboard_impl : public wax::obj{ -public: -    typedef boost::shared_ptr<usrp2_mboard_impl> sptr; - -    static const size_t NUM_RX_DSPS = 2; -    static const size_t NUM_TX_DSPS = 1; -    static const size_t MAX_NUM_DSPS = 2; - -    //structors -    usrp2_mboard_impl( -        const uhd::device_addr_t &device_addr, -        size_t index, usrp2_impl &device -    ); -    ~usrp2_mboard_impl(void); - -    inline double get_master_clock_freq(void){ -        return _clock_ctrl->get_master_clock_rate(); -    } - -    void handle_overflow(size_t); - -private: -    size_t _index; -    usrp2_impl &_device; -    bool _mimo_clocking_mode_is_master; - -    //interfaces -    usrp2_iface::sptr _iface; -    usrp2_clock_ctrl::sptr _clock_ctrl; -    usrp2_codec_ctrl::sptr _codec_ctrl; -    gps_ctrl::sptr _gps_ctrl; - -    //properties for this mboard -    void get(const wax::obj &, wax::obj &); -    void set(const wax::obj &, const wax::obj &); -    uhd::usrp::subdev_spec_t _rx_subdev_spec, _tx_subdev_spec; - -    //rx and tx dboard methods and objects -    uhd::usrp::dboard_manager::sptr _dboard_manager; -    uhd::usrp::dboard_iface::sptr _dboard_iface; -    void dboard_init(void); - -    //methods and shadows for clock configuration -    uhd::clock_config_t _clock_config; -    void update_clock_config(void); -    void set_time_spec(const uhd::time_spec_t &time_spec, bool now); - -    //properties interface for the codec -    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; -    wax_obj_proxy::sptr _tx_codec_proxy; - -    void rx_codec_set_gain(double, const std::string &); -    uhd::dict<std::string, double> _codec_rx_gains; - -    //properties interface for rx dboard -    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; -    uhd::usrp::dboard_eeprom_t _rx_db_eeprom; - -    //properties interface for tx dboard -    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; -    uhd::usrp::dboard_eeprom_t _tx_db_eeprom, _gdb_eeprom; - -    //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; -     -    //sensors methods for mboard -    bool get_mimo_locked(void); -    bool get_ref_locked(void); -}; - -/*!   * USRP2 implementation guts:   * The implementation details are encapsulated here.   * Handles device properties and streaming...   */  class usrp2_impl : public uhd::device{  public: -    static const size_t sram_bytes = size_t(1 << 20); -    static const boost::uint32_t RECV_SID = 1; -    static const boost::uint32_t ASYNC_SID = 2; -      usrp2_impl(const uhd::device_addr_t &); -      ~usrp2_impl(void);      //the io interface @@ -199,27 +87,50 @@ public:      size_t get_max_recv_samps_per_packet(void) const;      bool recv_async_msg(uhd::async_metadata_t &, double); -    void update_xport_channel_mapping(void); - -    //public frame sizes, set by mboard, used by io impl -    size_t recv_frame_size, send_frame_size; - -    std::vector<uhd::transport::zero_copy_if::sptr> dsp_xports; -    std::vector<uhd::transport::zero_copy_if::sptr> err_xports; -  private: -    //device properties interface -    void get(const wax::obj &, wax::obj &); -    void set(const wax::obj &, const wax::obj &); +    uhd::property_tree::sptr _tree; +    struct mb_container_type{ +        usrp2_iface::sptr iface; +        usrp2_clock_ctrl::sptr clock; +        usrp2_codec_ctrl::sptr codec; +        gps_ctrl::sptr gps; +        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; +        std::vector<uhd::transport::zero_copy_if::sptr> dsp_xports; +        std::vector<uhd::transport::zero_copy_if::sptr> err_xports; +        uhd::usrp::dboard_manager::sptr dboard_manager; +        uhd::usrp::dboard_iface::sptr dboard_iface; +        size_t rx_chan_occ, tx_chan_occ; +    }; +    uhd::dict<std::string, mb_container_type> _mbc; + +    void set_mb_eeprom(const std::string &, const uhd::usrp::mboard_eeprom_t &); +    void set_db_eeprom(const std::string &, const std::string &, const uhd::usrp::dboard_eeprom_t &); + +    uhd::sensor_value_t get_mimo_locked(const std::string &); +    uhd::sensor_value_t get_ref_locked(const std::string &); -    //pointers to mboards on this device (think mimo setup) -    std::vector<usrp2_mboard_impl::sptr> _mboards; -    uhd::dict<std::string, usrp2_mboard_impl::sptr> _mboard_dict; +    //device properties interface +    void get(const wax::obj &, wax::obj &val){ +        val = _tree; //entry point into property tree +    }      //io impl methods and members      uhd::otw_type_t _rx_otw_type, _tx_otw_type;      UHD_PIMPL_DECL(io_impl) _io_impl;      void io_init(void); +    void update_tick_rate(const double rate); +    void update_rx_samp_rate(const double rate); +    void update_tx_samp_rate(const double rate); +    //update spec methods are coercers until we only accept db_name == A +    uhd::usrp::subdev_spec_t update_rx_subdev_spec(const std::string &, const uhd::usrp::subdev_spec_t &); +    uhd::usrp::subdev_spec_t update_tx_subdev_spec(const std::string &, const uhd::usrp::subdev_spec_t &); +    double set_tx_dsp_freq(const std::string &, const double); +    uhd::meta_range_t get_tx_dsp_freq_range(const std::string &); +    void update_clock_source(const std::string &, const std::string &);  };  #endif /* INCLUDED_USRP2_IMPL_HPP */ diff --git a/host/lib/usrp/usrp2/usrp2_regs.hpp b/host/lib/usrp/usrp2/usrp2_regs.hpp index 19c1b45f1..a45a83a21 100644 --- a/host/lib/usrp/usrp2/usrp2_regs.hpp +++ b/host/lib/usrp/usrp2/usrp2_regs.hpp @@ -90,25 +90,6 @@  #define U2_FLAG_MISC_CTRL_ADC_OFF 0x00  ///////////////////////////////////////////////// -// VITA49 64 bit time (write only) -//////////////////////////////////////////////// -#define U2_REG_TIME64_SECS U2_REG_SR_ADDR(SR_TIME64 + 0) -#define U2_REG_TIME64_TICKS U2_REG_SR_ADDR(SR_TIME64 + 1) -#define U2_REG_TIME64_FLAGS U2_REG_SR_ADDR(SR_TIME64 + 2) -#define U2_REG_TIME64_IMM U2_REG_SR_ADDR(SR_TIME64 + 3) -#define U2_REG_TIME64_TPS U2_REG_SR_ADDR(SR_TIME64 + 4) -#define U2_REG_TIME64_MIMO_SYNC U2_REG_SR_ADDR(SR_TIME64 + 5) - -//pps flags (see above) -#define U2_FLAG_TIME64_PPS_NEGEDGE (0 << 0) -#define U2_FLAG_TIME64_PPS_POSEDGE (1 << 0) -#define U2_FLAG_TIME64_PPS_SMA     (0 << 1) -#define U2_FLAG_TIME64_PPS_MIMO    (1 << 1) - -#define U2_FLAG_TIME64_LATCH_NOW 1 -#define U2_FLAG_TIME64_LATCH_NEXT_PPS 0 - -/////////////////////////////////////////////////  // Readback regs  ////////////////////////////////////////////////  #define U2_REG_STATUS READBACK_BASE + 4*8 @@ -119,45 +100,6 @@  #define U2_REG_TIME64_SECS_RB_PPS READBACK_BASE + 4*14  #define U2_REG_TIME64_TICKS_RB_PPS READBACK_BASE + 4*15 -///////////////////////////////////////////////// -// RX FE -//////////////////////////////////////////////// -#define U2_REG_RX_FE_SWAP_IQ             U2_REG_SR_ADDR(SR_RX_FRONT + 0) //lower bit -#define U2_REG_RX_FE_MAG_CORRECTION      U2_REG_SR_ADDR(SR_RX_FRONT + 1) //18 bits -#define U2_REG_RX_FE_PHASE_CORRECTION    U2_REG_SR_ADDR(SR_RX_FRONT + 2) //18 bits -#define U2_REG_RX_FE_OFFSET_I            U2_REG_SR_ADDR(SR_RX_FRONT + 3) //18 bits -#define U2_REG_RX_FE_OFFSET_Q            U2_REG_SR_ADDR(SR_RX_FRONT + 4) //18 bits - -///////////////////////////////////////////////// -// TX FE -//////////////////////////////////////////////// -#define U2_REG_TX_FE_DC_OFFSET_I         U2_REG_SR_ADDR(SR_TX_FRONT + 0) //24 bits -#define U2_REG_TX_FE_DC_OFFSET_Q         U2_REG_SR_ADDR(SR_TX_FRONT + 1) //24 bits -#define U2_REG_TX_FE_MAC_CORRECTION      U2_REG_SR_ADDR(SR_TX_FRONT + 2) //18 bits -#define U2_REG_TX_FE_PHASE_CORRECTION    U2_REG_SR_ADDR(SR_TX_FRONT + 3) //18 bits -#define U2_REG_TX_FE_MUX                 U2_REG_SR_ADDR(SR_TX_FRONT + 4) //8 bits (std output = 0x10, reversed = 0x01) - -///////////////////////////////////////////////// -// DSP TX Regs -//////////////////////////////////////////////// -#define U2_REG_DSP_TX_FREQ U2_REG_SR_ADDR(SR_TX_DSP + 0) -#define U2_REG_DSP_TX_SCALE_IQ U2_REG_SR_ADDR(SR_TX_DSP + 1) -#define U2_REG_DSP_TX_INTERP_RATE U2_REG_SR_ADDR(SR_TX_DSP + 2) - -///////////////////////////////////////////////// -// DSP RX Regs -//////////////////////////////////////////////// -#define U2_REG_DSP_RX_HELPER(which, offset) ((which == 0)? \ -    (U2_REG_SR_ADDR(SR_RX_DSP0 + offset)) : \ -    (U2_REG_SR_ADDR(SR_RX_DSP1 + offset))) - -#define U2_REG_DSP_RX_FREQ(which)       U2_REG_DSP_RX_HELPER(which, 0) -#define U2_REG_DSP_RX_DECIM(which)      U2_REG_DSP_RX_HELPER(which, 2) -#define U2_REG_DSP_RX_MUX(which)        U2_REG_DSP_RX_HELPER(which, 3) - -#define U2_FLAG_DSP_RX_MUX_SWAP_IQ   (1 << 0) -#define U2_FLAG_DSP_RX_MUX_REAL_MODE (1 << 1) -  ////////////////////////////////////////////////  // GPIO  //////////////////////////////////////////////// @@ -184,38 +126,4 @@  #define U2_REG_ATR_FULL_TXSIDE ATR_BASE + 12  #define U2_REG_ATR_FULL_RXSIDE ATR_BASE + 14 -/////////////////////////////////////////////////// -// RX CTRL regs -/////////////////////////////////////////////////// -#define U2_REG_RX_CTRL_HELPER(which, offset) ((which == 0)? \ -    (U2_REG_SR_ADDR(SR_RX_CTRL0 + offset)) : \ -    (U2_REG_SR_ADDR(SR_RX_CTRL1 + offset))) - -#define U2_REG_RX_CTRL_STREAM_CMD(which)     U2_REG_RX_CTRL_HELPER(which, 0) -#define U2_REG_RX_CTRL_TIME_SECS(which)      U2_REG_RX_CTRL_HELPER(which, 1) -#define U2_REG_RX_CTRL_TIME_TICKS(which)     U2_REG_RX_CTRL_HELPER(which, 2) -#define U2_REG_RX_CTRL_CLEAR(which)          U2_REG_RX_CTRL_HELPER(which, 3) -#define U2_REG_RX_CTRL_VRT_HDR(which)        U2_REG_RX_CTRL_HELPER(which, 4) -#define U2_REG_RX_CTRL_VRT_SID(which)        U2_REG_RX_CTRL_HELPER(which, 5) -#define U2_REG_RX_CTRL_VRT_TLR(which)        U2_REG_RX_CTRL_HELPER(which, 6) -#define U2_REG_RX_CTRL_NSAMPS_PP(which)      U2_REG_RX_CTRL_HELPER(which, 7) -#define U2_REG_RX_CTRL_NCHANNELS(which)      U2_REG_RX_CTRL_HELPER(which, 8) - -/////////////////////////////////////////////////// -// TX CTRL regs -/////////////////////////////////////////////////// -#define U2_REG_TX_CTRL_NUM_CHAN U2_REG_SR_ADDR(SR_TX_CTRL + 0) -#define U2_REG_TX_CTRL_CLEAR_STATE U2_REG_SR_ADDR(SR_TX_CTRL + 1) -#define U2_REG_TX_CTRL_REPORT_SID U2_REG_SR_ADDR(SR_TX_CTRL + 2) -#define U2_REG_TX_CTRL_POLICY U2_REG_SR_ADDR(SR_TX_CTRL + 3) -#define U2_REG_TX_CTRL_CYCLES_PER_UP U2_REG_SR_ADDR(SR_TX_CTRL + 4) -#define U2_REG_TX_CTRL_PACKETS_PER_UP U2_REG_SR_ADDR(SR_TX_CTRL + 5) - -#define U2_FLAG_TX_CTRL_POLICY_WAIT          (0x1 << 0) -#define U2_FLAG_TX_CTRL_POLICY_NEXT_PACKET   (0x1 << 1) -#define U2_FLAG_TX_CTRL_POLICY_NEXT_BURST    (0x1 << 2) - -//enable flag for registers: cycles and packets per update packet -#define U2_FLAG_TX_CTRL_UP_ENB              (1ul << 31) -  #endif /* INCLUDED_USRP2_REGS_HPP */ | 
