diff options
Diffstat (limited to 'host/lib/usrp')
119 files changed, 26094 insertions, 0 deletions
diff --git a/host/lib/usrp/CMakeLists.txt b/host/lib/usrp/CMakeLists.txt new file mode 100644 index 000000000..8ae379f73 --- /dev/null +++ b/host/lib/usrp/CMakeLists.txt @@ -0,0 +1,39 @@ +# +# 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/>. +# + +######################################################################## +# This file included, use CMake directory variables +######################################################################## +LIBUHD_APPEND_SOURCES( +    ${CMAKE_CURRENT_SOURCE_DIR}/dboard_base.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/dboard_eeprom.cpp +    ${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}/gps_ctrl.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/mboard_eeprom.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/multi_usrp.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/subdev_spec.cpp +) + +INCLUDE_SUBDIRECTORY(cores) +INCLUDE_SUBDIRECTORY(dboard) +INCLUDE_SUBDIRECTORY(common) +INCLUDE_SUBDIRECTORY(usrp1) +INCLUDE_SUBDIRECTORY(usrp2) +INCLUDE_SUBDIRECTORY(b100) +INCLUDE_SUBDIRECTORY(e100) diff --git a/host/lib/usrp/README b/host/lib/usrp/README new file mode 100644 index 000000000..344209179 --- /dev/null +++ b/host/lib/usrp/README @@ -0,0 +1,15 @@ +######################################################################## +# lib USRP directories: +######################################################################## + +dboard: +    Daughterboard implementation code for all USRP daughterboards + +usrp1: +    Implementation code for the USB-based USRP Classic motherboard. + +usrp2: +    Implementation code for USRP2, USRP-N200, and USRP-N210. + +usrp_e100: +    Implementation code for USRP-E100. diff --git a/host/lib/usrp/b100/CMakeLists.txt b/host/lib/usrp/b100/CMakeLists.txt new file mode 100644 index 000000000..1237f52d1 --- /dev/null +++ b/host/lib/usrp/b100/CMakeLists.txt @@ -0,0 +1,36 @@ +# +# 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 +######################################################################## + +######################################################################## +# Conditionally configure the B100 support +######################################################################## +LIBUHD_REGISTER_COMPONENT("B100" ENABLE_B100 ON "ENABLE_LIBUHD;ENABLE_USB" OFF) + +IF(ENABLE_B100) +    LIBUHD_APPEND_SOURCES( +        ${CMAKE_CURRENT_SOURCE_DIR}/b100_ctrl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/b100_impl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/clock_ctrl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/codec_ctrl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/dboard_iface.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/io_impl.cpp +    ) +ENDIF(ENABLE_B100) diff --git a/host/lib/usrp/b100/b100_ctrl.cpp b/host/lib/usrp/b100/b100_ctrl.cpp new file mode 100644 index 000000000..e6136c00e --- /dev/null +++ b/host/lib/usrp/b100/b100_ctrl.cpp @@ -0,0 +1,257 @@ +// +// Copyright 2011 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "b100_ctrl.hpp" +#include <uhd/transport/bounded_buffer.hpp> +#include <uhd/transport/usb_zero_copy.hpp> +#include <uhd/transport/zero_copy.hpp> +#include <uhd/transport/vrt_if_packet.hpp> +#include <uhd/utils/thread_priority.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/utils/tasks.hpp> +#include <uhd/types/metadata.hpp> +#include <uhd/types/serial.hpp> +#include "ctrl_packet.hpp" +#include <boost/thread/thread.hpp> +#include <boost/bind.hpp> +#include <uhd/exception.hpp> + +using namespace uhd::transport; +using namespace uhd; + +bool b100_ctrl_debug = false; + +class b100_ctrl_impl : public b100_ctrl { +public: +    b100_ctrl_impl(uhd::transport::zero_copy_if::sptr ctrl_transport): +        sync_ctrl_fifo(2), +        _ctrl_transport(ctrl_transport), +        _seq(0) +    { +        viking_marauder = task::make(boost::bind(&b100_ctrl_impl::viking_marauder_loop, this)); +    } + +    ~b100_ctrl_impl(void){ +        //stop the marauder first so it cant access deconstructed objects +        viking_marauder.reset(); +    } + +    int write(boost::uint32_t addr, const ctrl_data_t &data); +    ctrl_data_t read(boost::uint32_t addr, size_t len); + +    bool get_ctrl_data(ctrl_data_t &pkt_data, double timeout); + +    void poke32(wb_addr_type addr, boost::uint32_t data){ +        boost::mutex::scoped_lock lock(_ctrl_mutex); + +        ctrl_data_t words(2); +        words[0] = data & 0x0000FFFF; +        words[1] = data >> 16; +        this->write(addr, words); +    } + +    boost::uint32_t peek32(wb_addr_type addr){ +        boost::mutex::scoped_lock lock(_ctrl_mutex); + +        ctrl_data_t words = this->read(addr, 2); +        return boost::uint32_t((boost::uint32_t(words[1]) << 16) | words[0]); +    } + +    void poke16(wb_addr_type addr, boost::uint16_t data){ +        boost::mutex::scoped_lock lock(_ctrl_mutex); + +        ctrl_data_t words(1); +        words[0] = data; +        this->write(addr, words); +    } + +    boost::uint16_t peek16(wb_addr_type addr){ +        boost::mutex::scoped_lock lock(_ctrl_mutex); + +        ctrl_data_t words = this->read(addr, 1); +        return boost::uint16_t(words[0]); +    } + +    void set_async_cb(const async_cb_type &async_cb){ +        boost::mutex::scoped_lock lock(_async_mutex); +        _async_cb = async_cb; +    } + +private: +    int send_pkt(boost::uint16_t *cmd); + +    //änd hërë wë gö ä-Vïkïng för äsynchronous control packets +    void viking_marauder_loop(void); +    bounded_buffer<ctrl_data_t> sync_ctrl_fifo; +    async_cb_type _async_cb; +    task::sptr viking_marauder; + +    uhd::transport::zero_copy_if::sptr _ctrl_transport; +    boost::uint8_t _seq; +    boost::mutex _ctrl_mutex, _async_mutex; +}; + +/*********************************************************************** + * helper functions for packing/unpacking control packets + **********************************************************************/ +void pack_ctrl_pkt(boost::uint16_t *pkt_buff, +                          const ctrl_pkt_t &pkt){ +    //first two bits are OP +    //next six bits are CALLBACKS +    //next 8 bits are SEQUENCE +    //next 16 bits are LENGTH (16-bit word) +    //next 32 bits are ADDRESS (16-bit word LSW) +    //then DATA (28 16-bit words) +    pkt_buff[0] = (boost::uint16_t(pkt.pkt_meta.op) << 14) | (boost::uint16_t(pkt.pkt_meta.callbacks) << 8) | pkt.pkt_meta.seq; +    pkt_buff[1] = pkt.pkt_meta.len; +    pkt_buff[2] = (pkt.pkt_meta.addr & 0x00000FFF); +    pkt_buff[3] = 0x0000; //address high bits always 0 on this device + +    for(size_t i = 0; i < pkt.data.size(); i++) { +        pkt_buff[4+i] = pkt.data[i]; +    } +} + +void unpack_ctrl_pkt(const boost::uint16_t *pkt_buff, +                            ctrl_pkt_t &pkt){ +    pkt.pkt_meta.seq = pkt_buff[0] & 0xFF; +    pkt.pkt_meta.op = CTRL_PKT_OP_READ; //really this is useless +    pkt.pkt_meta.len = pkt_buff[1]; +    pkt.pkt_meta.callbacks = 0; //callbacks aren't implemented yet +    pkt.pkt_meta.addr = pkt_buff[2] | boost::uint32_t(pkt_buff[3] << 16); + +    //let's check this so we don't go pushing 64K of crap onto the pkt +    if(pkt.pkt_meta.len > CTRL_PACKET_DATA_LENGTH) { +        throw uhd::runtime_error("Received control packet too long"); +    } + +    for(int i = 4; i < 4+pkt.pkt_meta.len; i++) pkt.data.push_back(pkt_buff[i]); +} + +int b100_ctrl_impl::send_pkt(boost::uint16_t *cmd) { +    managed_send_buffer::sptr sbuf = _ctrl_transport->get_send_buff(); +    if(!sbuf.get()) { +        throw uhd::runtime_error("Control channel send error"); +    } + +    //FIXME there's a better way to do this +    for(size_t i = 0; i < (CTRL_PACKET_LENGTH / sizeof(boost::uint16_t)); i++) { +        sbuf->cast<boost::uint16_t *>()[i] = cmd[i]; +    } +    sbuf->commit(CTRL_PACKET_LENGTH); //fixed size transaction +    return 0; +} + +int b100_ctrl_impl::write(boost::uint32_t addr, const ctrl_data_t &data) { +    UHD_ASSERT_THROW(data.size() <= (CTRL_PACKET_DATA_LENGTH / sizeof(boost::uint16_t))); +    ctrl_pkt_t pkt; +    pkt.data = data; +    pkt.pkt_meta.op = CTRL_PKT_OP_WRITE; +    pkt.pkt_meta.callbacks = 0; +    pkt.pkt_meta.seq = _seq++; +    pkt.pkt_meta.len = pkt.data.size(); +    pkt.pkt_meta.addr = addr; +    boost::uint16_t pkt_buff[CTRL_PACKET_LENGTH / sizeof(boost::uint16_t)] = {}; + +    pack_ctrl_pkt(pkt_buff, pkt); +    size_t result = send_pkt(pkt_buff); +    return result; +} + +ctrl_data_t b100_ctrl_impl::read(boost::uint32_t addr, size_t len) { +    UHD_ASSERT_THROW(len <= (CTRL_PACKET_DATA_LENGTH / sizeof(boost::uint16_t))); + +    ctrl_pkt_t pkt; +    pkt.pkt_meta.op = CTRL_PKT_OP_READ; +    pkt.pkt_meta.callbacks = 0; +    pkt.pkt_meta.seq = _seq++; +    pkt.pkt_meta.len = len; +    pkt.pkt_meta.addr = addr; +    boost::uint16_t pkt_buff[CTRL_PACKET_LENGTH / sizeof(boost::uint16_t)] = {}; + +    //flush anything that might be in the queue +    while (get_ctrl_data(pkt.data, 0.0)){ +        UHD_MSG(error) << "B100: control read found unexpected packet." << std::endl; +    } + +    pack_ctrl_pkt(pkt_buff, pkt); +    send_pkt(pkt_buff); + +    //block with timeout waiting for the response to appear +    if (not get_ctrl_data(pkt.data, 0.1)) throw uhd::runtime_error( +        "B100: timeout waiting for control response packet." +    ); + +    return pkt.data; +} + +/*********************************************************************** + * Viking marauders go pillaging for asynchronous control packets in the + * control response endpoint. Sync packets go in sync_ctrl_fifo, + * async TX error messages go in async_msg_fifo. sync_ctrl_fifo should + * never have more than 1 message in it, since it's expected that we'll + * wait for a control operation to finish before starting another one. + **********************************************************************/ +void b100_ctrl_impl::viking_marauder_loop(void){ +    set_thread_priority_safe(); + +    while (not boost::this_thread::interruption_requested()){ +        managed_recv_buffer::sptr rbuf = _ctrl_transport->get_recv_buff(1.0); +        if(rbuf.get() == NULL) continue; //that's ok, there are plenty of villages to pillage! +        const boost::uint16_t *pkt_buf = rbuf->cast<const boost::uint16_t *>(); + +        if(pkt_buf[0] >> 8 == CTRL_PACKET_HEADER_MAGIC) { +            //so it's got a control packet header, let's parse it. +            ctrl_pkt_t pkt; +            unpack_ctrl_pkt(pkt_buf, pkt); + +            if(pkt.pkt_meta.seq != boost::uint8_t(_seq - 1)) { +                UHD_MSG(error) +                    << "Sequence error on control channel." << std::endl +                    << "Exiting control loop." << std::endl +                ; +                return; +            } +            if(pkt.pkt_meta.len > (CTRL_PACKET_LENGTH - CTRL_PACKET_HEADER_LENGTH)) { +                UHD_MSG(error) +                    << "Control channel packet length too long" << std::endl +                    << "Exiting control loop." << std::endl +                ; +                return; +            } + +            //push it onto the queue +            sync_ctrl_fifo.push_with_pop_on_full(pkt.data); +        } +        else{ //otherwise let the async callback handle it +            boost::mutex::scoped_lock lock(_async_mutex); +            if (not _async_cb.empty()) _async_cb(rbuf); +        } +    } +} + +bool b100_ctrl_impl::get_ctrl_data(ctrl_data_t &pkt_data, double timeout){ +    boost::this_thread::disable_interruption di; //disable because the wait can throw +    return sync_ctrl_fifo.pop_with_timed_wait(pkt_data, timeout); +} + +/*********************************************************************** + * Public make function for b100_ctrl interface + **********************************************************************/ +b100_ctrl::sptr b100_ctrl::make(uhd::transport::zero_copy_if::sptr ctrl_transport){ +    return sptr(new b100_ctrl_impl(ctrl_transport)); +} diff --git a/host/lib/usrp/b100/b100_ctrl.hpp b/host/lib/usrp/b100/b100_ctrl.hpp new file mode 100644 index 000000000..74884d525 --- /dev/null +++ b/host/lib/usrp/b100/b100_ctrl.hpp @@ -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/>. +// + +#ifndef INCLUDED_B100_CTRL_HPP +#define INCLUDED_B100_CTRL_HPP + +#include "wb_iface.hpp" +#include <uhd/transport/usb_zero_copy.hpp> +#include <uhd/types/serial.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> +#include "ctrl_packet.hpp" +#include <boost/function.hpp> + +class b100_ctrl : boost::noncopyable, public wb_iface{ +public: +    typedef boost::shared_ptr<b100_ctrl> sptr; +    typedef boost::function<void(uhd::transport::managed_recv_buffer::sptr)> async_cb_type; + +    /*! +     * Make a USRP control object from a data transport +     * \param ctrl_transport a USB data transport +     * \return a new b100 control object +     */ +    static sptr make(uhd::transport::zero_copy_if::sptr ctrl_transport); + +    //! set an async callback for messages +    virtual void set_async_cb(const async_cb_type &async_cb) = 0; + +    /*! +     * Write a byte vector to an FPGA register +     * \param addr the FPGA register address +     * \param bytes the data to write +     * \return 0 on success, error code on failure +     */ +    virtual int write(boost::uint32_t addr, const ctrl_data_t &data) = 0; + +    /*! +     * Read a byte vector from an FPGA register (blocking read) +     * \param addr the FPGA register address +     * \param len the length of the read +     * \return a vector of bytes from the register(s) in question +     */ +    virtual ctrl_data_t read(boost::uint32_t addr, size_t len) = 0; + +    /*! +     * Get a sync ctrl packet (blocking) +     * \param the packet data buffer +     * \param the timeout value +     * \return true if it got something +     */ +    virtual bool get_ctrl_data(ctrl_data_t &pkt_data, double timeout) = 0; + +}; + +#endif /* INCLUDED_B100_CTRL_HPP */ diff --git a/host/lib/usrp/b100/b100_impl.cpp b/host/lib/usrp/b100/b100_impl.cpp new file mode 100644 index 000000000..eec777842 --- /dev/null +++ b/host/lib/usrp/b100/b100_impl.cpp @@ -0,0 +1,566 @@ +// +// Copyright 2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "apply_corrections.hpp" +#include "b100_impl.hpp" +#include "b100_ctrl.hpp" +#include "fpga_regs_standard.h" +#include "usrp_i2c_addr.h" +#include "usrp_commands.h" +#include <uhd/transport/usb_control.hpp> +#include "ctrl_packet.hpp" +#include <uhd/utils/msg.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/images.hpp> +#include <uhd/utils/safe_call.hpp> +#include <boost/format.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/filesystem.hpp> +#include <boost/thread/thread.hpp> +#include <boost/lexical_cast.hpp> +#include "b100_regs.hpp" +#include <cstdio> +#include <iostream> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; + +const boost::uint16_t B100_VENDOR_ID  = 0x2500; +const boost::uint16_t B100_PRODUCT_ID = 0x0002; +const boost::uint16_t FX2_VENDOR_ID    = 0x04b4; +const boost::uint16_t FX2_PRODUCT_ID   = 0x8613; +static const boost::posix_time::milliseconds REENUMERATION_TIMEOUT_MS(3000); + +/*********************************************************************** + * Discovery + **********************************************************************/ +static device_addrs_t b100_find(const device_addr_t &hint) +{ +    device_addrs_t b100_addrs; + +    //return an empty list of addresses when type is set to non-b100 +    if (hint.has_key("type") and hint["type"] != "b100") return b100_addrs; + +    //Return an empty list of addresses when an address is specified, +    //since an address is intended for a different, non-USB, device. +    if (hint.has_key("addr")) return b100_addrs; + +    unsigned int vid, pid; + +    if(hint.has_key("vid") && hint.has_key("pid") && hint.has_key("type") && hint["type"] == "b100") { +        sscanf(hint.get("vid").c_str(), "%x", &vid); +        sscanf(hint.get("pid").c_str(), "%x", &pid); +    } else { +        vid = B100_VENDOR_ID; +        pid = B100_PRODUCT_ID; +    } + +    // Important note: +    // The get device list calls are nested inside the for loop. +    // This allows the usb guts to decontruct when not in use, +    // so that re-enumeration after fw load can occur successfully. +    // This requirement is a courtesy of libusb1.0 on windows. + +    //find the usrps and load firmware +    size_t found = 0; +    BOOST_FOREACH(usb_device_handle::sptr handle, usb_device_handle::get_device_list(vid, pid)) { +        //extract the firmware path for the b100 +        std::string b100_fw_image; +        try{ +            b100_fw_image = find_image_path(hint.get("fw", B100_FW_FILE_NAME)); +        } +        catch(...){ +            UHD_MSG(warning) << boost::format("Could not locate B100 firmware. %s\n") % print_images_error(); +            return b100_addrs; +        } +        UHD_LOG << "the firmware image: " << b100_fw_image << std::endl; + +        usb_control::sptr control; +        try{control = usb_control::make(handle, 0);} +        catch(const uhd::exception &){continue;} //ignore claimed + +        fx2_ctrl::make(control)->usrp_load_firmware(b100_fw_image); +        found++; +    } + +    //get descriptors again with serial number, but using the initialized VID/PID now since we have firmware +    vid = B100_VENDOR_ID; +    pid = B100_PRODUCT_ID; + +    const boost::system_time timeout_time = boost::get_system_time() + REENUMERATION_TIMEOUT_MS; + +    //search for the device until found or timeout +    while (boost::get_system_time() < timeout_time and b100_addrs.empty() and found != 0) +    { +        BOOST_FOREACH(usb_device_handle::sptr handle, usb_device_handle::get_device_list(vid, pid)) +        { +            usb_control::sptr control; +            try{control = usb_control::make(handle, 0);} +            catch(const uhd::exception &){continue;} //ignore claimed + +            fx2_ctrl::sptr fx2_ctrl = fx2_ctrl::make(control); +            const mboard_eeprom_t mb_eeprom = mboard_eeprom_t(*fx2_ctrl, B100_EEPROM_MAP_KEY); +            device_addr_t new_addr; +            new_addr["type"] = "b100"; +            new_addr["name"] = mb_eeprom["name"]; +            new_addr["serial"] = handle->get_serial(); +            //this is a found b100 when the hint serial and name match or blank +            if ( +                (not hint.has_key("name")   or hint["name"]   == new_addr["name"]) and +                (not hint.has_key("serial") or hint["serial"] == new_addr["serial"]) +            ){ +                b100_addrs.push_back(new_addr); +            } +        } +    } + +    return b100_addrs; +} + +/*********************************************************************** + * 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){ +    size_t initialization_count = 0; +    b100_impl_constructor_begin: +    initialization_count++; + +    _tree = property_tree::make(); + +    //extract the FPGA path for the B100 +    std::string b100_fpga_image = find_image_path( +        device_addr.has_key("fpga")? device_addr["fpga"] : B100_FPGA_FILE_NAME +    ); + +    //try to match the given device address with something on the USB bus +    std::vector<usb_device_handle::sptr> device_list = +        usb_device_handle::get_device_list(B100_VENDOR_ID, B100_PRODUCT_ID); + +    //locate the matching handle in the device list +    usb_device_handle::sptr handle; +    BOOST_FOREACH(usb_device_handle::sptr dev_handle, device_list) { +        if (dev_handle->get_serial() == device_addr["serial"]){ +            handle = dev_handle; +            break; +        } +    } +    UHD_ASSERT_THROW(handle.get() != NULL); //better be found + +    //create control objects +    usb_control::sptr fx2_transport = usb_control::make(handle, 0); +    _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)); + +    //load FPGA image, slave xfers are disabled while loading +    this->enable_gpif(false); +    _fx2_ctrl->usrp_load_fpga(b100_fpga_image); +    _fx2_ctrl->usrp_fpga_reset(false); //active low reset +    _fx2_ctrl->usrp_fpga_reset(true); + +    //create the control transport +    device_addr_t ctrl_xport_args; +    ctrl_xport_args["recv_frame_size"] = boost::lexical_cast<std::string>(CTRL_PACKET_LENGTH); +    ctrl_xport_args["num_recv_frames"] = "16"; +    ctrl_xport_args["send_frame_size"] = boost::lexical_cast<std::string>(CTRL_PACKET_LENGTH); +    ctrl_xport_args["num_send_frames"] = "4"; + +    _ctrl_transport = usb_zero_copy::make( +        handle, +        4, 8, //interface, endpoint +        3, 4, //interface, endpoint +        ctrl_xport_args +    ); +    while (_ctrl_transport->get_recv_buff(0.0)){} //flush ctrl xport +    this->enable_gpif(true); + +    //////////////////////////////////////////////////////////////////// +    // Initialize FPGA wishbone communication +    //////////////////////////////////////////////////////////////////// +    _fpga_ctrl = b100_ctrl::make(_ctrl_transport); +    _fpga_ctrl->poke32(B100_REG_GLOBAL_RESET, 0); //global fpga reset +    //perform a test peek operation +    try{ +        _fpga_ctrl->peek32(0); +    } +    //try reset once in the case of failure +    catch(const uhd::exception &){ +        if (initialization_count > 1) throw; +        UHD_MSG(warning) << +            "The control endpoint was left in a bad state.\n" +            "Attempting endpoint re-enumeration...\n" << std::endl; +        _fpga_ctrl.reset(); +        _ctrl_transport.reset(); +        _fx2_ctrl->usrp_fx2_reset(); +        goto b100_impl_constructor_begin; +    } +    this->check_fpga_compat(); //check after reset and making control + +    //////////////////////////////////////////////////////////////////// +    // Initialize peripherals after reset +    //////////////////////////////////////////////////////////////////// +    _fpga_i2c_ctrl = i2c_core_100::make(_fpga_ctrl, B100_REG_SLAVE(3)); +    _fpga_spi_ctrl = spi_core_100::make(_fpga_ctrl, B100_REG_SLAVE(2)); + +    //////////////////////////////////////////////////////////////////// +    // Create data transport +    // This happens after FPGA ctrl instantiated so any junk that might +    // be in the FPGAs buffers doesn't get pulled into the transport +    // before being cleared. +    //////////////////////////////////////////////////////////////////// +    device_addr_t data_xport_args; +    data_xport_args["recv_frame_size"] = device_addr.get("recv_frame_size", "16384"); +    data_xport_args["num_recv_frames"] = device_addr.get("num_recv_frames", "16"); +    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"); + +    _data_transport = usb_zero_copy::make_wrapper( +        usb_zero_copy::make( +            handle,        // identifier +            2, 6,          // IN interface, endpoint +            1, 2,          // OUT interface, endpoint +            data_xport_args    // param hints +        ), +        B100_MAX_PKT_BYTE_LIMIT +    ); +    while (_data_transport->get_recv_buff(0.0)){} //flush data xport + +    //////////////////////////////////////////////////////////////////// +    // Initialize the properties tree +    //////////////////////////////////////////////////////////////////// +    _tree->create<std::string>("/name").set("B-Series Device"); +    const fs_path mb_path = "/mboards/0"; +    _tree->create<std::string>(mb_path / "name").set("B100"); +    _tree->create<std::string>(mb_path / "codename").set("B-Hundo"); +    _tree->create<std::string>(mb_path / "load_eeprom") +        .subscribe(boost::bind(&fx2_ctrl::usrp_load_eeprom, _fx2_ctrl, _1)); + +    //////////////////////////////////////////////////////////////////// +    // setup the mboard eeprom +    //////////////////////////////////////////////////////////////////// +    const mboard_eeprom_t mb_eeprom(*_fx2_ctrl, B100_EEPROM_MAP_KEY); +    _tree->create<mboard_eeprom_t>(mb_path / "eeprom") +        .set(mb_eeprom) +        .subscribe(boost::bind(&b100_impl::set_mb_eeprom, this, _1)); + +    //////////////////////////////////////////////////////////////////// +    // 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 fs_path rx_codec_path = mb_path / "rx_codecs/A"; +    const fs_path tx_codec_path = mb_path / "tx_codecs/A"; +    _tree->create<std::string>(rx_codec_path / "name").set("ad9522"); +    _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 +    //////////////////////////////////////////////////////////////////// +    _tree->create<sensor_value_t>(mb_path / "sensors/ref_locked") +        .publish(boost::bind(&b100_impl::get_ref_locked, this)); + +    //////////////////////////////////////////////////////////////////// +    // 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)); + +    _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)); + +    const fs_path rx_fe_path = mb_path / "rx_frontends" / "A"; +    const fs_path tx_fe_path = mb_path / "tx_frontends" / "A"; + +    _tree->create<std::complex<double> >(rx_fe_path / "dc_offset" / "value") +        .coerce(boost::bind(&rx_frontend_core_200::set_dc_offset, _rx_fe, _1)) +        .set(std::complex<double>(0.0, 0.0)); +    _tree->create<bool>(rx_fe_path / "dc_offset" / "enable") +        .subscribe(boost::bind(&rx_frontend_core_200::set_dc_offset_auto, _rx_fe, _1)) +        .set(true); +    _tree->create<std::complex<double> >(rx_fe_path / "iq_balance" / "value") +        .subscribe(boost::bind(&rx_frontend_core_200::set_iq_balance, _rx_fe, _1)) +        .set(std::complex<double>(0.0, 0.0)); +    _tree->create<std::complex<double> >(tx_fe_path / "dc_offset" / "value") +        .coerce(boost::bind(&tx_frontend_core_200::set_dc_offset, _tx_fe, _1)) +        .set(std::complex<double>(0.0, 0.0)); +    _tree->create<std::complex<double> >(tx_fe_path / "iq_balance" / "value") +        .subscribe(boost::bind(&tx_frontend_core_200::set_iq_balance, _tx_fe, _1)) +        .set(std::complex<double>(0.0, 0.0)); + +    //////////////////////////////////////////////////////////////////// +    // 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)); +        fs_path rx_dsp_path = mb_path / str(boost::format("rx_dsps/%u") % dspno); +        _tree->create<meta_range_t>(rx_dsp_path / "rate/range") +            .publish(boost::bind(&rx_dsp_core_200::get_host_rates, _rx_dsps[dspno])); +        _tree->create<double>(rx_dsp_path / "rate/value") +            .set(1e6) //some default +            .coerce(boost::bind(&rx_dsp_core_200::set_host_rate, _rx_dsps[dspno], _1)) +            .subscribe(boost::bind(&b100_impl::update_rx_samp_rate, this, dspno, _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 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<meta_range_t>(mb_path / "tx_dsps/0/rate/range") +        .publish(boost::bind(&tx_dsp_core_200::get_host_rates, _tx_dsp)); +    _tree->create<double>(mb_path / "tx_dsps/0/rate/value") +        .set(1e6) //some default +        .coerce(boost::bind(&tx_dsp_core_200::set_host_rate, _tx_dsp, _1)) +        .subscribe(boost::bind(&b100_impl::update_tx_samp_rate, this, 0, _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_hi_now = B100_REG_RB_TIME_NOW_HI; +    time64_rb_bases.rb_lo_now = B100_REG_RB_TIME_NOW_LO; +    time64_rb_bases.rb_hi_pps = B100_REG_RB_TIME_PPS_HI; +    time64_rb_bases.rb_lo_pps = B100_REG_RB_TIME_PPS_LO; +    _time64 = 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 user-defined control objects +    //////////////////////////////////////////////////////////////////// +    _user = user_settings_core_200::make(_fpga_ctrl, B100_REG_SR_ADDR(B100_SR_USER_REGS)); +    _tree->create<user_settings_core_200::user_reg_t>(mb_path / "user/regs") +        .subscribe(boost::bind(&user_settings_core_200::set_reg, _user, _1)); + +    //////////////////////////////////////////////////////////////////// +    // 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, tx_db_eeprom.id, gdb_eeprom.id, +        _dboard_iface, _tree->subtree(mb_path / "dboards/A") +    ); + +    //bind frontend corrections to the dboard freq props +    const fs_path db_tx_fe_path = mb_path / "dboards" / "A" / "tx_frontends"; +    BOOST_FOREACH(const std::string &name, _tree->list(db_tx_fe_path)){ +        _tree->access<double>(db_tx_fe_path / name / "freq" / "value") +            .subscribe(boost::bind(&b100_impl::set_tx_fe_corrections, this, _1)); +    } +    const fs_path db_rx_fe_path = mb_path / "dboards" / "A" / "rx_frontends"; +    BOOST_FOREACH(const std::string &name, _tree->list(db_rx_fe_path)){ +        _tree->access<double>(db_rx_fe_path / name / "freq" / "value") +            .subscribe(boost::bind(&b100_impl::set_rx_fe_corrections, this, _1)); +    } + +    //initialize io handling +    this->io_init(); + +    //////////////////////////////////////////////////////////////////// +    // do some post-init tasks +    //////////////////////////////////////////////////////////////////// +    this->update_rates(); + +    _tree->access<double>(mb_path / "tick_rate") //now subscribe the clock rate setter +        .subscribe(boost::bind(&b100_clock_ctrl::set_fpga_clock_rate, _clock_ctrl, _1)); + +    //reset cordic rates and their properties to zero +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){ +        _tree->access<double>(mb_path / "rx_dsps" / name / "freq" / "value").set(0.0); +    } +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +        _tree->access<double>(mb_path / "tx_dsps" / name / "freq" / "value").set(0.0); +    } + +    _tree->access<subdev_spec_t>(mb_path / "rx_subdev_spec").set(subdev_spec_t("A:" + _tree->list(mb_path / "dboards/A/rx_frontends").at(0))); +    _tree->access<subdev_spec_t>(mb_path / "tx_subdev_spec").set(subdev_spec_t("A:" + _tree->list(mb_path / "dboards/A/tx_frontends").at(0))); +    _tree->access<std::string>(mb_path / "clock_source/value").set("internal"); +    _tree->access<std::string>(mb_path / "time_source/value").set("none"); +} + +b100_impl::~b100_impl(void){ +    //set an empty async callback now that we deconstruct +    _fpga_ctrl->set_async_cb(b100_ctrl::async_cb_type()); +} + +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.\n" +            "%s" +        ) % B100_FW_COMPAT_NUM % fw_compat_num % print_images_error())); +    } +} + +void b100_impl::check_fpga_compat(void){ +    const boost::uint32_t fpga_compat_num = _fpga_ctrl->peek32(B100_REG_RB_COMPAT); +    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 != B100_FPGA_COMPAT_NUM){ +        throw uhd::runtime_error(str(boost::format( +            "Expected FPGA compatibility number %d, but got %d:\n" +            "The FPGA build is not compatible with the host code build." +            "%s" +        ) % int(B100_FPGA_COMPAT_NUM) % fpga_major % print_images_error())); +    } +    _tree->create<std::string>("/mboards/0/fpga_version").set(str(boost::format("%u.%u") % fpga_major % fpga_minor)); +} + +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'); +} + +void b100_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){ +    mb_eeprom.commit(*_fx2_ctrl, B100_EEPROM_MAP_KEY); +} + +void b100_impl::set_db_eeprom(const std::string &type, const uhd::usrp::dboard_eeprom_t &db_eeprom){ +    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); +} + +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); +} + +////////////////// some GPIF preparation related stuff ///////////////// +void b100_impl::enable_gpif(const bool en) { +    _fx2_ctrl->usrp_control_write(VRQ_ENABLE_GPIF, en ? 1 : 0, 0, 0, 0); +} + +void b100_impl::clear_fpga_fifo(void) { +    _fx2_ctrl->usrp_control_write(VRQ_CLEAR_FPGA_FIFO, 0, 0, 0, 0); +} + +sensor_value_t b100_impl::get_ref_locked(void){ +    const bool lock = _clock_ctrl->get_locked(); +    return sensor_value_t("Ref", lock, "locked", "unlocked"); +} + +void b100_impl::set_rx_fe_corrections(const double lo_freq){ +    apply_rx_fe_corrections(this->get_tree()->subtree("/mboards/0"), "A", lo_freq); +} + +void b100_impl::set_tx_fe_corrections(const double lo_freq){ +    apply_tx_fe_corrections(this->get_tree()->subtree("/mboards/0"), "A", lo_freq); +} diff --git a/host/lib/usrp/b100/b100_impl.hpp b/host/lib/usrp/b100/b100_impl.hpp new file mode 100644 index 000000000..22e22bcff --- /dev/null +++ b/host/lib/usrp/b100/b100_impl.hpp @@ -0,0 +1,135 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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_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 "user_settings_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/sensors.hpp> +#include <uhd/types/clock_config.hpp> +#include <uhd/types/stream_cmd.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> +#include <boost/weak_ptr.hpp> + +static const double          B100_LINK_RATE_BPS = 256e6/5; //pratical link rate (< 480 Mbps) +static const std::string     B100_FW_FILE_NAME = "usrp_b100_fw.ihx"; +static const std::string     B100_FPGA_FILE_NAME = "usrp_b100_fpga.bin"; +static const boost::uint16_t B100_FW_COMPAT_NUM = 0x03; +static const boost::uint16_t B100_FPGA_COMPAT_NUM = 10; +static const boost::uint32_t B100_RX_SID_BASE = 2; +static const boost::uint32_t B100_TX_ASYNC_SID = 1; +static const double          B100_DEFAULT_TICK_RATE = 64e6; +static const size_t          B100_MAX_PKT_BYTE_LIMIT = 2048; +static const std::string     B100_EEPROM_MAP_KEY = "B100"; + +//! Make a b100 dboard interface +uhd::usrp::dboard_iface::sptr make_b100_dboard_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 +); + +//! Implementation guts +class b100_impl : public uhd::device { +public: +    //structors +    b100_impl(const uhd::device_addr_t &); +    ~b100_impl(void); + +    //the io interface +    uhd::rx_streamer::sptr get_rx_stream(const uhd::stream_args_t &args); +    uhd::tx_streamer::sptr get_tx_stream(const uhd::stream_args_t &args); +    bool recv_async_msg(uhd::async_metadata_t &, double); + +private: +    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; +    user_settings_core_200::sptr _user; +    b100_clock_ctrl::sptr _clock_ctrl; +    b100_codec_ctrl::sptr _codec_ctrl; +    b100_ctrl::sptr _fpga_ctrl; +    uhd::usrp::fx2_ctrl::sptr _fx2_ctrl; + +    //transports +    uhd::transport::zero_copy_if::sptr _data_transport, _ctrl_transport; + +    //dboard stuff +    uhd::usrp::dboard_manager::sptr _dboard_manager; +    uhd::usrp::dboard_iface::sptr _dboard_iface; + +    //handle io stuff +    UHD_PIMPL_DECL(io_impl) _io_impl; +    void io_init(void); + +    //device properties interface +    uhd::property_tree::sptr get_tree(void) const{ +        return _tree; +    } + +    std::vector<boost::weak_ptr<uhd::rx_streamer> > _rx_streamers; +    std::vector<boost::weak_ptr<uhd::tx_streamer> > _tx_streamers; + +    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 size_t, const double rate); +    void update_tx_samp_rate(const size_t, const double rate); +    void update_rates(void); +    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 enable_gpif(const bool); +    void clear_fpga_fifo(void); +    void handle_async_message(uhd::transport::managed_recv_buffer::sptr); +    uhd::sensor_value_t get_ref_locked(void); +    void set_rx_fe_corrections(const double); +    void set_tx_fe_corrections(const double); +}; + +#endif /* INCLUDED_b100_IMPL_HPP */ diff --git a/host/lib/usrp/b100/b100_regs.hpp b/host/lib/usrp/b100/b100_regs.hpp new file mode 100644 index 000000000..987a09f03 --- /dev/null +++ b/host/lib/usrp/b100/b100_regs.hpp @@ -0,0 +1,123 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +//////////////////////////////////////////////////////////////// +// +//         Memory map for wishbone bus +// +//////////////////////////////////////////////////////////////// + +// All addresses are byte addresses.  All accesses are word (16-bit) accesses. +//  This means that address bit 0 is usually 0. +//  There are 11 bits of address for the control. + +#ifndef INCLUDED_B100_REGS_HPP +#define INCLUDED_B100_REGS_HPP + +///////////////////////////////////////////////////// +// Slave pointers + +#define B100_REG_SLAVE(n) ((n)<<7) + +///////////////////////////////////////////////////// +// Slave 0 -- Misc Regs + +#define B100_REG_MISC_BASE B100_REG_SLAVE(0) + +#define B100_REG_MISC_LED        B100_REG_MISC_BASE + 0 +#define B100_REG_MISC_SW         B100_REG_MISC_BASE + 2 +#define B100_REG_MISC_CGEN_CTRL  B100_REG_MISC_BASE + 4 +#define B100_REG_MISC_CGEN_ST    B100_REG_MISC_BASE + 6 + +///////////////////////////////////////////////////// +// Slave 1 -- UART +//   CLKDIV is 16 bits, others are only 8 + +#define B100_REG_UART_BASE B100_REG_SLAVE(1) + +#define B100_REG_UART_CLKDIV  B100_REG_UART_BASE + 0 +#define B100_REG_UART_TXLEVEL B100_REG_UART_BASE + 2 +#define B100_REG_UART_RXLEVEL B100_REG_UART_BASE + 4 +#define B100_REG_UART_TXCHAR  B100_REG_UART_BASE + 6 +#define B100_REG_UART_RXCHAR  B100_REG_UART_BASE + 8 + +///////////////////////////////////////////////////// +// Slave 2 -- SPI Core +//these are 32-bit registers mapped onto the 16-bit Wishbone bus.  +//Using peek32/poke32 should allow transparent use of these registers. +#define B100_REG_SPI_BASE B100_REG_SLAVE(2) + +//spi slave constants +#define B100_SPI_SS_AD9862    (1 << 2) +#define B100_SPI_SS_TX_DB     (1 << 1) +#define B100_SPI_SS_RX_DB     (1 << 0) + +//////////////////////////////////////////////// +// Slave 3 -- I2C Core + +#define B100_REG_I2C_BASE B100_REG_SLAVE(3) + +/////////////////////////////////////////////////// +// Slave 7 -- Readback Mux 32 + +#define B100_REG_RB_MUX_32_BASE  B100_REG_SLAVE(7) + +#define B100_REG_RB_TIME_NOW_HI     B100_REG_RB_MUX_32_BASE + 0 +#define B100_REG_RB_TIME_NOW_LO     B100_REG_RB_MUX_32_BASE + 4 +#define B100_REG_RB_TIME_PPS_HI     B100_REG_RB_MUX_32_BASE + 8 +#define B100_REG_RB_TIME_PPS_LO     B100_REG_RB_MUX_32_BASE + 12 +#define B100_REG_RB_MISC_TEST32     B100_REG_RB_MUX_32_BASE + 16 +#define B100_REG_RB_COMPAT          B100_REG_RB_MUX_32_BASE + 24 +#define B100_REG_RB_GPIO            B100_REG_RB_MUX_32_BASE + 28 + +//////////////////////////////////////////////////// +// Slaves 8 & 9 -- Settings Bus +// +// Output-only, no readback, 64 registers total +//  Each register must be written 32 bits at a time +//  First the address xxx_xx00 and then xxx_xx10 +// 64 total regs in address space +#define B100_SR_RX_CTRL0 0       // 9 regs (+0 to +8) +#define B100_SR_RX_DSP0 10       // 4 regs (+0 to +3) +#define B100_SR_RX_CTRL1 16      // 9 regs (+0 to +8) +#define B100_SR_RX_DSP1 26       // 4 regs (+0 to +3) +#define B100_SR_TX_CTRL 32       // 4 regs (+0 to +3) +#define B100_SR_TX_DSP 38        // 3 regs (+0 to +2) + +#define B100_SR_TIME64 42        // 6 regs (+0 to +5) +#define B100_SR_RX_FRONT 48      // 5 regs (+0 to +4) +#define B100_SR_TX_FRONT 54      // 5 regs (+0 to +4) + +#define B100_SR_REG_TEST32 60    // 1 reg +#define B100_SR_CLEAR_FIFO 61    // 1 reg +#define B100_SR_GLOBAL_RESET 63  // 1 reg +#define B100_SR_USER_REGS 64     // 2 regs + +#define B100_SR_GPIO 128 + +#define B100_REG_SR_ADDR(n) (B100_REG_SLAVE(8) + (4*(n))) + +#define B100_REG_SR_MISC_TEST32        B100_REG_SR_ADDR(B100_SR_REG_TEST32) + +///////////////////////////////////////////////// +// Magic reset regs +//////////////////////////////////////////////// +#define B100_REG_CLEAR_FIFO         B100_REG_SR_ADDR(B100_SR_CLEAR_FIFO) +#define B100_REG_GLOBAL_RESET       B100_REG_SR_ADDR(B100_SR_GLOBAL_RESET) + +#endif + diff --git a/host/lib/usrp/b100/clock_ctrl.cpp b/host/lib/usrp/b100/clock_ctrl.cpp new file mode 100644 index 000000000..cbe6c40a0 --- /dev/null +++ b/host/lib/usrp/b100/clock_ctrl.cpp @@ -0,0 +1,536 @@ +// +// 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 "clock_ctrl.hpp" +#include "ad9522_regs.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/safe_call.hpp> +#include <boost/cstdint.hpp> +#include "b100_regs.hpp" //spi slave constants +#include <boost/assign/list_of.hpp> +#include <boost/foreach.hpp> +#include <boost/format.hpp> +#include <boost/thread/thread.hpp> +#include <boost/math/common_factor_rt.hpp> //gcd +#include <algorithm> +#include <utility> + +using namespace uhd; + +/*********************************************************************** + * Constants + **********************************************************************/ +static const bool ENABLE_THE_TEST_OUT = true; +static const double REFERENCE_INPUT_RATE = 10e6; + +/*********************************************************************** + * Helpers + **********************************************************************/ +template <typename div_type, typename bypass_type> static void set_clock_divider( +    size_t divider, div_type &low, div_type &high, bypass_type &bypass +){ +    high = divider/2 - 1; +    low = divider - high - 2; +    bypass = (divider == 1)? 1 : 0; +} + +/*********************************************************************** + * Clock rate calculation stuff: + *   Using the internal VCO between 1400 and 1800 MHz + **********************************************************************/ +struct clock_settings_type{ +    size_t ref_clock_doubler, r_counter, a_counter, b_counter, prescaler, vco_divider, chan_divider; +    size_t get_n_counter(void) const{return prescaler * b_counter + a_counter;} +    double get_ref_rate(void) const{return REFERENCE_INPUT_RATE * ref_clock_doubler;} +    double get_vco_rate(void) const{return get_ref_rate()/r_counter * get_n_counter();} +    double get_chan_rate(void) const{return get_vco_rate()/vco_divider;} +    double get_out_rate(void) const{return get_chan_rate()/chan_divider;} +    std::string to_pp_string(void) const{ +        return str(boost::format( +            "  r_counter: %d\n" +            "  a_counter: %d\n" +            "  b_counter: %d\n" +            "  prescaler: %d\n" +            "  vco_divider: %d\n" +            "  chan_divider: %d\n" +            "  vco_rate: %fMHz\n" +            "  chan_rate: %fMHz\n" +            "  out_rate: %fMHz\n" +            ) +            % r_counter +            % a_counter +            % b_counter +            % prescaler +            % vco_divider +            % chan_divider +            % (get_vco_rate()/1e6) +            % (get_chan_rate()/1e6) +            % (get_out_rate()/1e6) +        ); +    } +}; + +//! gives the greatest divisor of num between 1 and max inclusive +template<typename T> static inline T greatest_divisor(T num, T max){ +    for (T i = max; i > 1; i--) if (num%i == 0) return i; return 1; +} + +//! gives the least divisor of num between min and num exclusive +template<typename T> static inline T least_divisor(T num, T min){ +    for (T i = min; i < num; i++) if (num%i == 0) return i; return 1; +} + +static clock_settings_type get_clock_settings(double rate){ +    clock_settings_type cs; +    cs.ref_clock_doubler = 2; //always doubling +    cs.prescaler = 8; //set to 8 when input is under 2400 MHz + +    //basic formulas used below: +    //out_rate*X = ref_rate*Y +    //X = i*ref_rate/gcd +    //Y = i*out_rate/gcd +    //X = chan_div * vco_div * R +    //Y = P*B + A + +    const boost::uint64_t out_rate = boost::uint64_t(rate); +    const boost::uint64_t ref_rate = boost::uint64_t(cs.get_ref_rate()); +    const size_t gcd = size_t(boost::math::gcd(ref_rate, out_rate)); + +    for (size_t i = 1; i <= 100; i++){ +        const size_t X = i*ref_rate/gcd; +        const size_t Y = i*out_rate/gcd; + +        //determine A and B (P is fixed) +        cs.b_counter = Y/cs.prescaler; +        cs.a_counter = Y - cs.b_counter*cs.prescaler; + +        static const double vco_bound_pad = 100e6; +        for ( //calculate an r divider that fits into the bounds of the vco +            cs.r_counter  = size_t(cs.get_n_counter()*cs.get_ref_rate()/(1800e6 - vco_bound_pad)); +            cs.r_counter <= size_t(cs.get_n_counter()*cs.get_ref_rate()/(1400e6 + vco_bound_pad)) +            and cs.r_counter > 0; cs.r_counter++ +        ){ + +            //determine chan_div and vco_div +            //and fill in that order of preference +            cs.chan_divider = greatest_divisor<size_t>(X/cs.r_counter, 32); +            cs.vco_divider = greatest_divisor<size_t>(X/cs.chan_divider/cs.r_counter, 6); + +            //avoid a vco divider of 1 (if possible) +            if (cs.vco_divider == 1){ +                cs.vco_divider = least_divisor<size_t>(cs.chan_divider, 2); +                cs.chan_divider /= cs.vco_divider; +            } + +            UHD_LOGV(always) +                << "gcd " << gcd << std::endl +                << "X " << X << std::endl +                << "Y " << Y << std::endl +                << cs.to_pp_string() << std::endl +            ; + +            //filter limits on the counters +            if (cs.vco_divider == 1) continue; +            if (cs.r_counter >= (1<<14)) continue; +            if (cs.b_counter == 2) continue; +            if (cs.b_counter == 1 and cs.a_counter != 0) continue; +            if (cs.b_counter >= (1<<13)) continue; +            if (cs.a_counter >= (1<<6)) continue; +            if (cs.get_vco_rate() > 1800e6 - vco_bound_pad) continue; +            if (cs.get_vco_rate() < 1400e6 + vco_bound_pad) continue; +            if (cs.get_out_rate() != rate) continue; + +            UHD_MSG(status) << "USRP-B100 clock control: " << i << std::endl << cs.to_pp_string() << std::endl; +            return cs; +        } +    } + +    throw uhd::value_error(str(boost::format( +        "USRP-B100 clock control: could not calculate settings for clock rate %fMHz" +    ) % (rate/1e6))); +} + +/*********************************************************************** + * Clock Control Implementation + **********************************************************************/ +class b100_clock_ctrl_impl : public b100_clock_ctrl{ +public: +    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 +        _ad9522_regs.status_pin_control = 0x1; //n divider +        _ad9522_regs.ld_pin_control = 0x00; //dld +        _ad9522_regs.refmon_pin_control = 0x12; //show ref2 +        _ad9522_regs.lock_detect_counter = ad9522_regs_t::LOCK_DETECT_COUNTER_16CYC; + +        this->use_internal_ref(); + +        this->set_fpga_clock_rate(master_clock_rate); //initialize to something + +        this->enable_fpga_clock(true); +        this->enable_test_clock(ENABLE_THE_TEST_OUT); +        this->enable_rx_dboard_clock(false); +        this->enable_tx_dboard_clock(false); +    } + +    ~b100_clock_ctrl_impl(void){ +        UHD_SAFE_CALL( +            this->enable_test_clock(ENABLE_THE_TEST_OUT); +            this->enable_rx_dboard_clock(false); +            this->enable_tx_dboard_clock(false); +            //this->enable_fpga_clock(false); //FIXME +        ) +    } + +    /*********************************************************************** +     * Clock rate control: +     *  - set clock rate w/ internal VCO +     *  - set clock rate w/ external VCXO +     **********************************************************************/ +    void set_clock_settings_with_internal_vco(double rate){ +        const clock_settings_type cs = get_clock_settings(rate); + +        //set the rates to private variables so the implementation knows! +        _chan_rate = cs.get_chan_rate(); +        _out_rate = cs.get_out_rate(); + +        _ad9522_regs.enable_clock_doubler = (cs.ref_clock_doubler == 2)? 1 : 0; + +        _ad9522_regs.set_r_counter(cs.r_counter); +        _ad9522_regs.a_counter = cs.a_counter; +        _ad9522_regs.set_b_counter(cs.b_counter); +        UHD_ASSERT_THROW(cs.prescaler == 8); //assumes this below: +        _ad9522_regs.prescaler_p = ad9522_regs_t::PRESCALER_P_DIV8_9; + +        _ad9522_regs.pll_power_down = ad9522_regs_t::PLL_POWER_DOWN_NORMAL; +        _ad9522_regs.cp_current = ad9522_regs_t::CP_CURRENT_1_2MA; + +        _ad9522_regs.bypass_vco_divider = 0; +        switch(cs.vco_divider){ +        case 1: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV1; break; +        case 2: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV2; break; +        case 3: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV3; break; +        case 4: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV4; break; +        case 5: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV5; break; +        case 6: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV6; break; +        } +        _ad9522_regs.select_vco_or_clock = ad9522_regs_t::SELECT_VCO_OR_CLOCK_VCO; + +        //setup fpga master clock +        _ad9522_regs.out0_format = ad9522_regs_t::OUT0_FORMAT_LVDS; +        set_clock_divider(cs.chan_divider, +            _ad9522_regs.divider0_low_cycles, +            _ad9522_regs.divider0_high_cycles, +            _ad9522_regs.divider0_bypass +        ); + +        //setup codec clock +        _ad9522_regs.out3_format = ad9522_regs_t::OUT3_FORMAT_LVDS; +        set_clock_divider(cs.chan_divider, +            _ad9522_regs.divider1_low_cycles, +            _ad9522_regs.divider1_high_cycles, +            _ad9522_regs.divider1_bypass +        ); + +        this->send_all_regs(); +        calibrate_now(); +    } + +    void set_clock_settings_with_external_vcxo(double rate){ +        //set the rates to private variables so the implementation knows! +        _chan_rate = rate; +        _out_rate = rate; + +        _ad9522_regs.enable_clock_doubler = 1; //doubler always on +        const double ref_rate = REFERENCE_INPUT_RATE*2; + +        //bypass prescaler such that N = B +        long gcd = boost::math::gcd(long(ref_rate), long(rate)); +        _ad9522_regs.set_r_counter(int(ref_rate/gcd)); +        _ad9522_regs.a_counter = 0; +        _ad9522_regs.set_b_counter(int(rate/gcd)); +        _ad9522_regs.prescaler_p = ad9522_regs_t::PRESCALER_P_DIV1; + +        //setup external vcxo +        _ad9522_regs.pll_power_down = ad9522_regs_t::PLL_POWER_DOWN_NORMAL; +        _ad9522_regs.cp_current = ad9522_regs_t::CP_CURRENT_1_2MA; +        _ad9522_regs.bypass_vco_divider = 1; +        _ad9522_regs.select_vco_or_clock = ad9522_regs_t::SELECT_VCO_OR_CLOCK_EXTERNAL; + +        //setup fpga master clock +        _ad9522_regs.out0_format = ad9522_regs_t::OUT0_FORMAT_LVDS; +        _ad9522_regs.divider0_bypass = 1; + +        //setup codec clock +        _ad9522_regs.out3_format = ad9522_regs_t::OUT3_FORMAT_LVDS; +        _ad9522_regs.divider1_bypass = 1; + +        this->send_all_regs(); +    } + +    void set_fpga_clock_rate(double rate){ +        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); +    } + +    double get_fpga_clock_rate(void){ +        return this->_out_rate; +    } + +    /*********************************************************************** +     * FPGA clock enable +     **********************************************************************/ +    void enable_fpga_clock(bool enb){ +        _ad9522_regs.out0_format = ad9522_regs_t::OUT0_FORMAT_LVDS; +        _ad9522_regs.out0_lvds_power_down = !enb; +        this->send_reg(0x0F0); +        this->latch_regs(); +    } + +    /*********************************************************************** +     * Special test clock output +     **********************************************************************/ +    void enable_test_clock(bool enb){ +        //setup test clock (same divider as codec clock) +        _ad9522_regs.out4_format = ad9522_regs_t::OUT4_FORMAT_CMOS; +        _ad9522_regs.out4_cmos_configuration = (enb)? +            ad9522_regs_t::OUT4_CMOS_CONFIGURATION_A_ON : +            ad9522_regs_t::OUT4_CMOS_CONFIGURATION_OFF; +        this->send_reg(0x0F4); +        this->latch_regs(); +    } + +    /*********************************************************************** +     * RX Dboard Clock Control (output 9, divider 3) +     **********************************************************************/ +    void enable_rx_dboard_clock(bool enb){ +        _ad9522_regs.out9_format = ad9522_regs_t::OUT9_FORMAT_LVDS; +        _ad9522_regs.out9_lvds_power_down = !enb; +        this->send_reg(0x0F9); +        this->latch_regs(); +    } + +    std::vector<double> get_rx_dboard_clock_rates(void){ +        std::vector<double> rates; +        for(size_t div = 1; div <= 16+16; div++) +            rates.push_back(this->_chan_rate/div); +        return rates; +    } + +    void set_rx_dboard_clock_rate(double rate){ +        assert_has(get_rx_dboard_clock_rates(), rate, "rx dboard clock rate"); +        _rx_clock_rate = rate; +        size_t divider = size_t(this->_chan_rate/rate); +        //set the divider registers +        set_clock_divider(divider, +            _ad9522_regs.divider3_low_cycles, +            _ad9522_regs.divider3_high_cycles, +            _ad9522_regs.divider3_bypass +        ); +        this->send_reg(0x199); +        this->send_reg(0x19a); +        this->soft_sync(); +    } + +    double get_rx_clock_rate(void){ +        return _rx_clock_rate; +    } + +    /*********************************************************************** +     * TX Dboard Clock Control (output 6, divider 2) +     **********************************************************************/ +    void enable_tx_dboard_clock(bool enb){ +        _ad9522_regs.out6_format = ad9522_regs_t::OUT6_FORMAT_LVDS; +        _ad9522_regs.out6_lvds_power_down = !enb; +        this->send_reg(0x0F6); +        this->latch_regs(); +    } + +    std::vector<double> get_tx_dboard_clock_rates(void){ +        return get_rx_dboard_clock_rates(); //same master clock, same dividers... +    } + +    void set_tx_dboard_clock_rate(double rate){ +        assert_has(get_tx_dboard_clock_rates(), rate, "tx dboard clock rate"); +        _tx_clock_rate = rate; +        size_t divider = size_t(this->_chan_rate/rate); +        //set the divider registers +        set_clock_divider(divider, +            _ad9522_regs.divider2_low_cycles, +            _ad9522_regs.divider2_high_cycles, +            _ad9522_regs.divider2_bypass +        ); +        this->send_reg(0x196); +        this->send_reg(0x197); +        this->soft_sync(); +    } + +    double get_tx_clock_rate(void){ +        return _tx_clock_rate; +    } + +    /*********************************************************************** +     * Clock reference control +     **********************************************************************/ +    void use_internal_ref(void) { +        _ad9522_regs.enable_ref2 = 1; +        _ad9522_regs.enable_ref1 = 0; +        _ad9522_regs.select_ref = ad9522_regs_t::SELECT_REF_REF2; +        _ad9522_regs.enb_auto_ref_switchover = ad9522_regs_t::ENB_AUTO_REF_SWITCHOVER_MANUAL; +        this->send_reg(0x01C); +        this->latch_regs(); +    } + +    void use_external_ref(void) { +        _ad9522_regs.enable_ref2 = 0; +        _ad9522_regs.enable_ref1 = 1; +        _ad9522_regs.select_ref = ad9522_regs_t::SELECT_REF_REF1; +        _ad9522_regs.enb_auto_ref_switchover = ad9522_regs_t::ENB_AUTO_REF_SWITCHOVER_MANUAL; +        this->send_reg(0x01C); +        this->latch_regs(); +    } + +    void use_auto_ref(void) { +        _ad9522_regs.enable_ref2 = 1; +        _ad9522_regs.enable_ref1 = 1; +        _ad9522_regs.select_ref = ad9522_regs_t::SELECT_REF_REF1; +        _ad9522_regs.enb_auto_ref_switchover = ad9522_regs_t::ENB_AUTO_REF_SWITCHOVER_AUTO; +        this->send_reg(0x01C); +        this->latch_regs(); +    } + +    bool get_locked(void){ +        static const boost::uint8_t addr = 0x01F; +        boost::uint32_t reg = this->read_reg(addr); +        _ad9522_regs.set_reg(addr, reg); +        return _ad9522_regs.digital_lock_detect != 0; +    } + +private: +    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 +    double _rx_clock_rate, _tx_clock_rate; + +    void latch_regs(void){ +        _ad9522_regs.io_update = 1; +        this->send_reg(0x232); +    } + +    void send_reg(boost::uint16_t addr){ +        boost::uint32_t reg = _ad9522_regs.get_write_reg(addr); +        UHD_LOGV(often) << "clock control write reg: " << std::hex << reg << std::endl; +        byte_vector_t buf; +        buf.push_back(boost::uint8_t(reg >> 16)); +        buf.push_back(boost::uint8_t(reg >> 8)); +        buf.push_back(boost::uint8_t(reg & 0xff)); + +        _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->write_i2c(0x5C, buf); + +        buf = _iface->read_i2c(0x5C, 1); + +        return boost::uint32_t(buf[0] & 0xFF); +    } + +    void calibrate_now(void){ +        //vco calibration routine: +        _ad9522_regs.vco_calibration_now = 0; +        this->send_reg(0x18); +        this->latch_regs(); +        _ad9522_regs.vco_calibration_now = 1; +        this->send_reg(0x18); +        this->latch_regs(); +        //wait for calibration done: +        static const boost::uint8_t addr = 0x01F; +        for (size_t ms10 = 0; ms10 < 100; ms10++){ +            boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +            boost::uint32_t reg = read_reg(addr); +            _ad9522_regs.set_reg(addr, reg); +            if (_ad9522_regs.vco_calibration_finished) goto wait_for_ld; +        } +        UHD_MSG(error) << "USRP-B100 clock control: VCO calibration timeout" << std::endl; +        wait_for_ld: +        //wait for digital lock detect: +        for (size_t ms10 = 0; ms10 < 100; ms10++){ +            boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +            boost::uint32_t reg = read_reg(addr); +            _ad9522_regs.set_reg(addr, reg); +            if (_ad9522_regs.digital_lock_detect) return; +        } +        UHD_MSG(error) << "USRP-B100 clock control: lock detection timeout" << std::endl; +    } + +    void soft_sync(void){ +        _ad9522_regs.soft_sync = 1; +        this->send_reg(0x230); +        this->latch_regs(); +        _ad9522_regs.soft_sync = 0; +        this->send_reg(0x230); +        this->latch_regs(); +    } + +    void send_all_regs(void){ +        //setup a list of register ranges to write +        typedef std::pair<boost::uint16_t, boost::uint16_t> range_t; +        static const std::vector<range_t> ranges = boost::assign::list_of +            (range_t(0x000, 0x000)) (range_t(0x010, 0x01F)) +            (range_t(0x0F0, 0x0FD)) (range_t(0x190, 0x19B)) +            (range_t(0x1E0, 0x1E1)) (range_t(0x230, 0x230)) +        ; + +        //write initial register values and latch/update +        BOOST_FOREACH(const range_t &range, ranges){ +            for(boost::uint16_t addr = range.first; addr <= range.second; addr++){ +                this->send_reg(addr); +            } +        } +        this->latch_regs(); +    } +}; + +/*********************************************************************** + * Clock Control Make + **********************************************************************/ +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 new file mode 100644 index 000000000..387892bf7 --- /dev/null +++ b/host/lib/usrp/b100/clock_ctrl.hpp @@ -0,0 +1,133 @@ +// +// 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_CLOCK_CTRL_HPP +#define INCLUDED_B100_CLOCK_CTRL_HPP + +#include <uhd/types/serial.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> +#include <vector> + +/*! + * The usrp-e clock control: + * - Setup system clocks. + * - Disable/enable clock lines. + */ +class b100_clock_ctrl : boost::noncopyable{ +public: +    typedef boost::shared_ptr<b100_clock_ctrl> sptr; + +    /*! +     * Make a new clock control 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(uhd::i2c_iface::sptr iface, double master_clock_rate); + +    /*! +     * Set the rate of the fpga clock line. +     * Throws if rate is not valid. +     * \param rate the new rate in Hz +     */ +    virtual void set_fpga_clock_rate(double rate) = 0; + +    /*! +     * Get the rate of the fpga clock line. +     * \return the fpga clock rate in Hz +     */ +    virtual double get_fpga_clock_rate(void) = 0; + +    /*! +     * Get the possible rates of the rx dboard clock. +     * \return a vector of clock rates in Hz +     */ +    virtual std::vector<double> get_rx_dboard_clock_rates(void) = 0; + +    /*! +     * Get the possible rates of the tx dboard clock. +     * \return a vector of clock rates in Hz +     */ +    virtual std::vector<double> get_tx_dboard_clock_rates(void) = 0; + +    /*! +     * Set the rx dboard clock rate to a possible rate. +     * \param rate the new clock rate in Hz +     * \throw exception when rate cannot be achieved +     */ +    virtual void set_rx_dboard_clock_rate(double rate) = 0; + +    /*! +     * Set the tx dboard clock rate to a possible rate. +     * \param rate the new clock rate in Hz +     * \throw exception when rate cannot be achieved +     */ +    virtual void set_tx_dboard_clock_rate(double rate) = 0; + +    /*! +     * Get the current rx dboard clock rate. +     * \return the clock rate in Hz +     */ +    virtual double get_rx_clock_rate(void) = 0; + +    /*! +     * Get the current tx dboard clock rate. +     * \return the clock rate in Hz +     */ +    virtual double get_tx_clock_rate(void) = 0; +     +    /*! +     * Enable/disable the FPGA clock. +     * \param enb true to enable +     */ +     +    virtual void enable_fpga_clock(bool enb) = 0; + +    /*! +     * Enable/disable the rx dboard clock. +     * \param enb true to enable +     */ +    virtual void enable_rx_dboard_clock(bool enb) = 0; + +    /*! +     * Enable/disable the tx dboard clock. +     * \param enb true to enable +     */ +    virtual void enable_tx_dboard_clock(bool enb) = 0; +     +    /*! +     * Use the internal TCXO reference +     */ +    virtual void use_internal_ref(void) = 0; +     +    /*! +     * Use the external SMA reference +     */ +    virtual void use_external_ref(void) = 0; +     +    /*! +     * Use external if available, internal otherwise +     */ +    virtual void use_auto_ref(void) = 0; + +    //! Is the reference locked? +    virtual bool get_locked(void) = 0; + +}; + +#endif /* INCLUDED_B100_CLOCK_CTRL_HPP */ diff --git a/host/lib/usrp/b100/codec_ctrl.cpp b/host/lib/usrp/b100/codec_ctrl.cpp new file mode 100644 index 000000000..278713ce1 --- /dev/null +++ b/host/lib/usrp/b100/codec_ctrl.cpp @@ -0,0 +1,283 @@ +// +// 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 "codec_ctrl.hpp" +#include "ad9862_regs.hpp" +#include <uhd/types/dict.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/utils/log.hpp> +#include <uhd/utils/safe_call.hpp> +#include <boost/cstdint.hpp> +#include <boost/tuple/tuple.hpp> +#include <boost/math/special_functions/round.hpp> +#include "b100_regs.hpp" //spi slave constants +#include <boost/assign/list_of.hpp> + +using namespace uhd; + +const gain_range_t b100_codec_ctrl::tx_pga_gain_range(-20, 0, double(0.1)); +const gain_range_t b100_codec_ctrl::rx_pga_gain_range(0, 20, 1); + +/*********************************************************************** + * Codec Control Implementation + **********************************************************************/ +class b100_codec_ctrl_impl : public b100_codec_ctrl{ +public: +    //structors +    b100_codec_ctrl_impl(spi_iface::sptr iface); +    ~b100_codec_ctrl_impl(void); + +    //aux adc and dac control +    double read_aux_adc(aux_adc_t which); +    void write_aux_dac(aux_dac_t which, double volts); + +    //pga gain control +    void set_tx_pga_gain(double); +    double get_tx_pga_gain(void); +    void set_rx_pga_gain(double, char); +    double get_rx_pga_gain(char); + +private: +    spi_iface::sptr _iface; +    ad9862_regs_t _ad9862_regs; +    void send_reg(boost::uint8_t addr); +    void recv_reg(boost::uint8_t addr); +}; + +/*********************************************************************** + * Codec Control Structors + **********************************************************************/ +b100_codec_ctrl_impl::b100_codec_ctrl_impl(spi_iface::sptr iface){ +    _iface = iface; + +    //soft reset +    _ad9862_regs.soft_reset = 1; +    this->send_reg(0); + +    //initialize the codec register settings +    _ad9862_regs.sdio_bidir = ad9862_regs_t::SDIO_BIDIR_SDIO_SDO; +    _ad9862_regs.lsb_first = ad9862_regs_t::LSB_FIRST_MSB; +    _ad9862_regs.soft_reset = 0; + +    //setup rx side of codec +    _ad9862_regs.byp_buffer_a = 1; +    _ad9862_regs.byp_buffer_b = 1; +    _ad9862_regs.buffer_a_pd = 1; +    _ad9862_regs.buffer_b_pd = 1; +    _ad9862_regs.mux_out = ad9862_regs_t::MUX_OUT_RX_MUX_MODE; //B100 uses interleaved RX->FPGA +    _ad9862_regs.rx_pga_a = 0;//0x1f;  //TODO bring under api control +    _ad9862_regs.rx_pga_b = 0;//0x1f;  //TODO bring under api control +    _ad9862_regs.rx_twos_comp = 1; +    _ad9862_regs.rx_hilbert = ad9862_regs_t::RX_HILBERT_DIS; + +    //setup tx side of codec +    _ad9862_regs.two_data_paths = ad9862_regs_t::TWO_DATA_PATHS_BOTH; +    _ad9862_regs.interleaved = ad9862_regs_t::INTERLEAVED_INTERLEAVED; +    _ad9862_regs.tx_retime = ad9862_regs_t::TX_RETIME_CLKOUT2; +    _ad9862_regs.tx_pga_gain = 199; //TODO bring under api control +    _ad9862_regs.tx_hilbert = ad9862_regs_t::TX_HILBERT_DIS; +    _ad9862_regs.interp = ad9862_regs_t::INTERP_2; +    _ad9862_regs.tx_twos_comp = 1; +    _ad9862_regs.fine_mode = ad9862_regs_t::FINE_MODE_BYPASS; +    _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_BYPASS; +    _ad9862_regs.dac_a_coarse_gain = 0x3; +    _ad9862_regs.dac_b_coarse_gain = 0x3; +    _ad9862_regs.edges = ad9862_regs_t::EDGES_NORMAL; + +    //setup the dll +    _ad9862_regs.input_clk_ctrl = ad9862_regs_t::INPUT_CLK_CTRL_EXTERNAL; +    _ad9862_regs.dll_mult = ad9862_regs_t::DLL_MULT_2; +    _ad9862_regs.dll_mode = ad9862_regs_t::DLL_MODE_FAST; + +    //write the register settings to the codec +    for (boost::uint8_t addr = 0; addr <= 25; addr++){ +        this->send_reg(addr); +    } + +    //always start conversions for aux ADC +    _ad9862_regs.start_a = 1; +    _ad9862_regs.start_b = 1; + +    //aux adc clock +    _ad9862_regs.clk_4 = ad9862_regs_t::CLK_4_1_4; +    this->send_reg(34); +} + +b100_codec_ctrl_impl::~b100_codec_ctrl_impl(void){ +    UHD_SAFE_CALL( +        //set aux dacs to zero +        this->write_aux_dac(AUX_DAC_A, 0); +        this->write_aux_dac(AUX_DAC_B, 0); +        this->write_aux_dac(AUX_DAC_C, 0); +        this->write_aux_dac(AUX_DAC_D, 0); + +        //power down +        _ad9862_regs.all_rx_pd = 1; +        this->send_reg(1); +        _ad9862_regs.tx_digital_pd = 1; +        _ad9862_regs.tx_analog_pd = ad9862_regs_t::TX_ANALOG_PD_BOTH; +        this->send_reg(8); +    ) +} + +/*********************************************************************** + * Codec Control Gain Control Methods + **********************************************************************/ +static const int mtpgw = 255; //maximum tx pga gain word + +void b100_codec_ctrl_impl::set_tx_pga_gain(double gain){ +    int gain_word = int(mtpgw*(gain - tx_pga_gain_range.start())/(tx_pga_gain_range.stop() - tx_pga_gain_range.start())); +    _ad9862_regs.tx_pga_gain = uhd::clip(gain_word, 0, mtpgw); +    this->send_reg(16); +} + +double b100_codec_ctrl_impl::get_tx_pga_gain(void){ +    return (_ad9862_regs.tx_pga_gain*(tx_pga_gain_range.stop() - tx_pga_gain_range.start())/mtpgw) + tx_pga_gain_range.start(); +} + +static const int mrpgw = 0x14; //maximum rx pga gain word + +void b100_codec_ctrl_impl::set_rx_pga_gain(double gain, char which){ +    int gain_word = int(mrpgw*(gain - rx_pga_gain_range.start())/(rx_pga_gain_range.stop() - rx_pga_gain_range.start())); +    gain_word = uhd::clip(gain_word, 0, mrpgw); +    switch(which){ +    case 'A': +        _ad9862_regs.rx_pga_a = gain_word; +        this->send_reg(2); +        return; +    case 'B': +        _ad9862_regs.rx_pga_b = gain_word; +        this->send_reg(3); +        return; +    default: UHD_THROW_INVALID_CODE_PATH(); +    } +} + +double b100_codec_ctrl_impl::get_rx_pga_gain(char which){ +    int gain_word; +    switch(which){ +    case 'A': gain_word = _ad9862_regs.rx_pga_a; break; +    case 'B': gain_word = _ad9862_regs.rx_pga_b; break; +    default: UHD_THROW_INVALID_CODE_PATH(); +    } +    return (gain_word*(rx_pga_gain_range.stop() - rx_pga_gain_range.start())/mrpgw) + rx_pga_gain_range.start(); +} + +/*********************************************************************** + * Codec Control AUX ADC Methods + **********************************************************************/ +static double aux_adc_to_volts(boost::uint8_t high, boost::uint8_t low){ +    return double((boost::uint16_t(high) << 2) | low)*3.3/0x3ff; +} + +double b100_codec_ctrl_impl::read_aux_adc(aux_adc_t which){ +    switch(which){ + +    case AUX_ADC_A1: +        _ad9862_regs.select_a = ad9862_regs_t::SELECT_A_AUX_ADC1; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(28); //read the value (2 bytes, 2 reads) +        this->recv_reg(29); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_a1_9_2, _ad9862_regs.aux_adc_a1_1_0); +    case AUX_ADC_A2: +        _ad9862_regs.select_a = ad9862_regs_t::SELECT_A_AUX_ADC2; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(26); //read the value (2 bytes, 2 reads) +        this->recv_reg(27); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_a2_9_2, _ad9862_regs.aux_adc_a2_1_0); + +    case AUX_ADC_B1: +        _ad9862_regs.select_b = ad9862_regs_t::SELECT_B_AUX_ADC1; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(32); //read the value (2 bytes, 2 reads) +        this->recv_reg(33); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_b1_9_2, _ad9862_regs.aux_adc_b1_1_0); +    case AUX_ADC_B2: +        _ad9862_regs.select_b = ad9862_regs_t::SELECT_B_AUX_ADC2; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(30); //read the value (2 bytes, 2 reads) +        this->recv_reg(31); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_b2_9_2, _ad9862_regs.aux_adc_b2_1_0); +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +/*********************************************************************** + * Codec Control AUX DAC Methods + **********************************************************************/ +void b100_codec_ctrl_impl::write_aux_dac(aux_dac_t which, double volts){ +    //special case for aux dac d (aka sigma delta word) +    if (which == AUX_DAC_D){ +        boost::uint16_t dac_word = uhd::clip(boost::math::iround(volts*0xfff/3.3), 0, 0xfff); +        _ad9862_regs.sig_delt_11_4 = boost::uint8_t(dac_word >> 4); +        _ad9862_regs.sig_delt_3_0 = boost::uint8_t(dac_word & 0xf); +        this->send_reg(42); +        this->send_reg(43); +        return; +    } + +    //calculate the dac word for aux dac a, b, c +    boost::uint8_t dac_word = uhd::clip(boost::math::iround(volts*0xff/3.3), 0, 0xff); + +    //setup a lookup table for the aux dac params (reg ref, reg addr) +    typedef boost::tuple<boost::uint8_t*, boost::uint8_t> dac_params_t; +    uhd::dict<aux_dac_t, dac_params_t> aux_dac_to_params = boost::assign::map_list_of +        (AUX_DAC_A, dac_params_t(&_ad9862_regs.aux_dac_a, 36)) +        (AUX_DAC_B, dac_params_t(&_ad9862_regs.aux_dac_b, 37)) +        (AUX_DAC_C, dac_params_t(&_ad9862_regs.aux_dac_c, 38)) +    ; + +    //set the aux dac register +    UHD_ASSERT_THROW(aux_dac_to_params.has_key(which)); +    boost::uint8_t *reg_ref, reg_addr; +    boost::tie(reg_ref, reg_addr) = aux_dac_to_params[which]; +    *reg_ref = dac_word; +    this->send_reg(reg_addr); +} + +/*********************************************************************** + * Codec Control SPI Methods + **********************************************************************/ +void b100_codec_ctrl_impl::send_reg(boost::uint8_t addr){ +    boost::uint32_t reg = _ad9862_regs.get_write_reg(addr); +    UHD_LOGV(rarely) << "codec control write reg: " << std::hex << reg << std::endl; +    _iface->transact_spi( +        B100_SPI_SS_AD9862, +        spi_config_t::EDGE_RISE, +        reg, 16, false /*no rb*/ +    ); +} + +void b100_codec_ctrl_impl::recv_reg(boost::uint8_t addr){ +    boost::uint32_t reg = _ad9862_regs.get_read_reg(addr); +    UHD_LOGV(rarely) << "codec control read reg: " << std::hex << reg << std::endl; +    boost::uint32_t ret = _iface->transact_spi( +        B100_SPI_SS_AD9862, +        spi_config_t::EDGE_RISE, +        reg, 16, true /*rb*/ +    ); +    UHD_LOGV(rarely) << "codec control read ret: " << std::hex << boost::uint16_t(ret & 0xFF) << std::endl; +    _ad9862_regs.set_reg(addr, boost::uint8_t(ret&0xff)); +} + +/*********************************************************************** + * Codec Control Make + **********************************************************************/ +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 new file mode 100644 index 000000000..1f7bdef09 --- /dev/null +++ b/host/lib/usrp/b100/codec_ctrl.hpp @@ -0,0 +1,90 @@ +// +// 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_CODEC_CTRL_HPP +#define INCLUDED_B100_CODEC_CTRL_HPP + +#include <uhd/types/serial.hpp> +#include <uhd/types/ranges.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> + +/*! + * The usrp-e codec control: + * - Init/power down codec. + * - Read aux adc, write aux dac. + */ +class b100_codec_ctrl : boost::noncopyable{ +public: +    typedef boost::shared_ptr<b100_codec_ctrl> sptr; + +    static const uhd::gain_range_t tx_pga_gain_range; +    static const uhd::gain_range_t rx_pga_gain_range; + +    /*! +     * Make a new codec control object. +     * \param iface the usrp_e iface object +     * \return the codec control object +     */ +    static sptr make(uhd::spi_iface::sptr iface); + +    //! aux adc identifier constants +    enum aux_adc_t{ +        AUX_ADC_A2 = 0xA2, +        AUX_ADC_A1 = 0xA1, +        AUX_ADC_B2 = 0xB2, +        AUX_ADC_B1 = 0xB1 +    }; + +    /*! +     * Read an auxiliary adc: +     * The internals remember which aux adc was read last. +     * Therefore, the aux adc switch is only changed as needed. +     * \param which which of the 4 adcs +     * \return a value in volts +     */ +    virtual double read_aux_adc(aux_adc_t which) = 0; + +    //! aux dac identifier constants +    enum aux_dac_t{ +        AUX_DAC_A = 0xA, +        AUX_DAC_B = 0xB, +        AUX_DAC_C = 0xC, +        AUX_DAC_D = 0xD //really the sigma delta output +    }; + +    /*! +     * Write an auxiliary dac. +     * \param which which of the 4 dacs +     * \param volts the level in in volts +     */ +    virtual void write_aux_dac(aux_dac_t which, double volts) = 0; + +    //! Set the TX PGA gain +    virtual void set_tx_pga_gain(double gain) = 0; + +    //! Get the TX PGA gain +    virtual double get_tx_pga_gain(void) = 0; + +    //! Set the RX PGA gain ('A' or 'B') +    virtual void set_rx_pga_gain(double gain, char which) = 0; + +    //! Get the RX PGA gain ('A' or 'B') +    virtual double get_rx_pga_gain(char which) = 0; +}; + +#endif /* INCLUDED_B100_CODEC_CTRL_HPP */ diff --git a/host/lib/usrp/b100/ctrl_packet.hpp b/host/lib/usrp/b100/ctrl_packet.hpp new file mode 100644 index 000000000..bab1f0de1 --- /dev/null +++ b/host/lib/usrp/b100/ctrl_packet.hpp @@ -0,0 +1,75 @@ +// +// Copyright 2011 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_CTRL_PACKET_HPP +#define INCLUDED_CTRL_PACKET_HPP + +#include <uhd/config.hpp> +#include <boost/cstdint.hpp> +#include <uhd/types/serial.hpp> + +typedef std::vector<boost::uint16_t> ctrl_data_t; + +/*! + * Control packet operation type + */ +enum ctrl_pkt_op_t {  +    CTRL_PKT_OP_WRITE = 1, +    CTRL_PKT_OP_READ = 2, +    CTRL_PKT_OP_READBACK = 3 +}; + +/*! + * Control packet transaction length + */ +const size_t CTRL_PACKET_LENGTH = 32; +const size_t CTRL_PACKET_HEADER_LENGTH = 8; +const size_t CTRL_PACKET_DATA_LENGTH = 24; //=length-header + +/*! + * Control packet header magic value + */ +const boost::uint8_t CTRL_PACKET_HEADER_MAGIC = 0xAA; + +/*!  + * Callback triggers for readback operation + */ +//FIXME: these are not real numbers, callbacks aren't implemented yet +const boost::uint16_t CTRL_PACKET_CALLBACK_SPI = 0x0001; +const boost::uint16_t CTRL_PACKET_CALLBACK_I2C = 0x0002; +//and so on + +/*! + * Metadata structure to describe a control packet + */ +struct UHD_API ctrl_pkt_meta_t { +    ctrl_pkt_op_t op; +    boost::uint8_t callbacks; +    boost::uint8_t seq; +    boost::uint16_t len; +    boost::uint32_t addr; +}; + +/*!  + * Full control packet structure + */ +struct UHD_API ctrl_pkt_t { +    ctrl_pkt_meta_t pkt_meta; +    ctrl_data_t data; +}; + +#endif /* INCLUDED_CTRL_PACKET_HPP */ diff --git a/host/lib/usrp/b100/dboard_iface.cpp b/host/lib/usrp/b100/dboard_iface.cpp new file mode 100644 index 000000000..39ad5c5ac --- /dev/null +++ b/host/lib/usrp/b100/dboard_iface.cpp @@ -0,0 +1,258 @@ +// +// 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 "gpio_core_200.hpp" +#include <uhd/types/serial.hpp> +#include "b100_regs.hpp" +#include "clock_ctrl.hpp" +#include "codec_ctrl.hpp" +#include <uhd/usrp/dboard_iface.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/exception.hpp> +#include <boost/assign/list_of.hpp> + + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +class b100_dboard_iface : public dboard_iface{ +public: + +    b100_dboard_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 +    ){ +        _wb_iface = wb_iface; +        _i2c_iface = i2c_iface; +        _spi_iface = spi_iface; +        _clock = clock; +        _codec = codec; +        _gpio = gpio_core_200::make(_wb_iface, B100_REG_SR_ADDR(B100_SR_GPIO), B100_REG_RB_GPIO); + +        //init the clock rate shadows +        this->set_clock_rate(UNIT_RX, _clock->get_fpga_clock_rate()); +        this->set_clock_rate(UNIT_TX, _clock->get_fpga_clock_rate()); +    } + +    ~b100_dboard_iface(void){ +        /* NOP */ +    } + +    special_props_t get_special_props(void){ +        special_props_t props; +        props.soft_clock_divider = false; +        props.mangle_i2c_addrs = false; +        return props; +    } + +    void write_aux_dac(unit_t, aux_dac_t, double); +    double read_aux_adc(unit_t, aux_adc_t); + +    void _set_pin_ctrl(unit_t, boost::uint16_t); +    void _set_atr_reg(unit_t, atr_reg_t, boost::uint16_t); +    void _set_gpio_ddr(unit_t, boost::uint16_t); +    void _set_gpio_out(unit_t, boost::uint16_t); +    void set_gpio_debug(unit_t, int); +    boost::uint16_t read_gpio(unit_t); + +    void write_i2c(boost::uint8_t, const byte_vector_t &); +    byte_vector_t read_i2c(boost::uint8_t, size_t); + +    void write_spi( +        unit_t unit, +        const spi_config_t &config, +        boost::uint32_t data, +        size_t num_bits +    ); + +    boost::uint32_t read_write_spi( +        unit_t unit, +        const spi_config_t &config, +        boost::uint32_t data, +        size_t num_bits +    ); + +    void set_clock_rate(unit_t, double); +    std::vector<double> get_clock_rates(unit_t); +    double get_clock_rate(unit_t); +    void set_clock_enabled(unit_t, bool); +    double get_codec_rate(unit_t); + +private: +    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; +    gpio_core_200::sptr _gpio; +}; + +/*********************************************************************** + * Make Function + **********************************************************************/ +dboard_iface::sptr make_b100_dboard_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(wb_iface, i2c_iface, spi_iface, clock, codec)); +} + +/*********************************************************************** + * Clock Rates + **********************************************************************/ +void b100_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> b100_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(); +    default: UHD_THROW_INVALID_CODE_PATH(); +    } +} + +double b100_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(); +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +void b100_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 b100_dboard_iface::get_codec_rate(unit_t){ +    return _clock->get_fpga_clock_rate(); +} + +/*********************************************************************** + * GPIO + **********************************************************************/ +void b100_dboard_iface::_set_pin_ctrl(unit_t unit, boost::uint16_t value){ +    return _gpio->set_pin_ctrl(unit, value); +} + +void b100_dboard_iface::_set_gpio_ddr(unit_t unit, boost::uint16_t value){ +    return _gpio->set_gpio_ddr(unit, value); +} + +void b100_dboard_iface::_set_gpio_out(unit_t unit, boost::uint16_t value){ +    return _gpio->set_gpio_out(unit, value); +} + +boost::uint16_t b100_dboard_iface::read_gpio(unit_t unit){ +    return _gpio->read_gpio(unit); +} + +void b100_dboard_iface::_set_atr_reg(unit_t unit, atr_reg_t atr, boost::uint16_t value){ +    return _gpio->set_atr_reg(unit, atr, value); +} + +void b100_dboard_iface::set_gpio_debug(unit_t, int){ +    throw uhd::not_implemented_error("no set_gpio_debug implemented"); +} + +/*********************************************************************** + * SPI + **********************************************************************/ +/*! + * Static function to convert a unit type to a spi slave device number. + * \param unit the dboard interface unit type enum + * \return the slave device number + */ +static boost::uint32_t unit_to_otw_spi_dev(dboard_iface::unit_t unit){ +    switch(unit){ +    case dboard_iface::UNIT_TX: return B100_SPI_SS_TX_DB; +    case dboard_iface::UNIT_RX: return B100_SPI_SS_RX_DB; +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +void b100_dboard_iface::write_spi( +    unit_t unit, +    const spi_config_t &config, +    boost::uint32_t data, +    size_t num_bits +){ +    _spi_iface->write_spi(unit_to_otw_spi_dev(unit), config, data, num_bits); +} + +boost::uint32_t b100_dboard_iface::read_write_spi( +    unit_t unit, +    const spi_config_t &config, +    boost::uint32_t data, +    size_t num_bits +){ +    return _spi_iface->read_spi(unit_to_otw_spi_dev(unit), config, data, num_bits); +} + +/*********************************************************************** + * I2C + **********************************************************************/ +void b100_dboard_iface::write_i2c(boost::uint8_t addr, const byte_vector_t &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 _i2c_iface->read_i2c(addr, num_bytes); +} + +/*********************************************************************** + * Aux DAX/ADC + **********************************************************************/ +void b100_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, b100_codec_ctrl::aux_dac_t> which_to_aux_dac = map_list_of +        (AUX_DAC_A, b100_codec_ctrl::AUX_DAC_A) +        (AUX_DAC_B, b100_codec_ctrl::AUX_DAC_B) +        (AUX_DAC_C, b100_codec_ctrl::AUX_DAC_C) +        (AUX_DAC_D, b100_codec_ctrl::AUX_DAC_D) +    ; +    _codec->write_aux_dac(which_to_aux_dac[which], value); +} + +double b100_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, b100_codec_ctrl::aux_adc_t> +    > unit_to_which_to_aux_adc = map_list_of +        (UNIT_RX, map_list_of +            (AUX_ADC_A, b100_codec_ctrl::AUX_ADC_A1) +            (AUX_ADC_B, b100_codec_ctrl::AUX_ADC_B1) +        ) +        (UNIT_TX, map_list_of +            (AUX_ADC_A, b100_codec_ctrl::AUX_ADC_A2) +            (AUX_ADC_B, b100_codec_ctrl::AUX_ADC_B2) +        ) +    ; +    return _codec->read_aux_adc(unit_to_which_to_aux_adc[unit][which]); +} diff --git a/host/lib/usrp/b100/io_impl.cpp b/host/lib/usrp/b100/io_impl.cpp new file mode 100644 index 000000000..674380cca --- /dev/null +++ b/host/lib/usrp/b100/io_impl.cpp @@ -0,0 +1,295 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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 "validate_subdev_spec.hpp" +#include "async_packet_handler.hpp" +#include "../../transport/super_recv_packet_handler.hpp" +#include "../../transport/super_send_packet_handler.hpp" +#include "usrp_commands.h" +#include "b100_impl.hpp" +#include "b100_regs.hpp" +#include <uhd/utils/thread_priority.hpp> +#include <uhd/transport/bounded_buffer.hpp> +#include <boost/bind.hpp> +#include <boost/format.hpp> +#include <boost/bind.hpp> +#include <boost/thread.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp> +#include <boost/make_shared.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; + +/*********************************************************************** + * IO Implementation Details + **********************************************************************/ +struct b100_impl::io_impl{ +    io_impl(void): +        async_msg_fifo(1000/*messages deep*/) +    { /* NOP */ } + +    zero_copy_if::sptr data_transport; +    bounded_buffer<async_metadata_t> async_msg_fifo; +    recv_packet_demuxer::sptr demuxer; +    double tick_rate; +}; + +/*********************************************************************** + * Initialize internals within this file + **********************************************************************/ +void b100_impl::io_init(void){ + +    //clear fifo state machines +    _fpga_ctrl->poke32(B100_REG_CLEAR_FIFO, 0); + +    //allocate streamer weak ptrs containers +    _rx_streamers.resize(_rx_dsps.size()); +    _tx_streamers.resize(1/*known to be 1 dsp*/); + +    //create new io impl +    _io_impl = UHD_PIMPL_MAKE(io_impl, ()); +    _io_impl->demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), B100_RX_SID_BASE); + +    //now its safe to register the async callback +    _fpga_ctrl->set_async_cb(boost::bind(&b100_impl::handle_async_message, this, _1)); +} + +void b100_impl::handle_async_message(managed_recv_buffer::sptr rbuf){ +    vrt::if_packet_info_t if_packet_info; +    if_packet_info.num_packet_words32 = rbuf->size()/sizeof(boost::uint32_t); +    const boost::uint32_t *vrt_hdr = rbuf->cast<const boost::uint32_t *>(); +    try{ +        vrt::if_hdr_unpack_le(vrt_hdr, if_packet_info); +    } +    catch(const std::exception &e){ +        UHD_MSG(error) << "Error (handle_async_message): " << e.what() << std::endl; +    } + +    if (if_packet_info.sid == B100_TX_ASYNC_SID and if_packet_info.packet_type != vrt::if_packet_info_t::PACKET_TYPE_DATA){ + +        //fill in the async metadata +        async_metadata_t metadata; +        load_metadata_from_buff(uhd::wtohx<boost::uint32_t>, metadata, if_packet_info, vrt_hdr, _io_impl->tick_rate); + +        //push the message onto the queue +        _io_impl->async_msg_fifo.push_with_pop_on_full(metadata); + +        //print some fastpath messages +        standard_async_msg_prints(metadata); +    } +    else UHD_MSG(error) << "Unknown async packet" << std::endl; +} + +void b100_impl::update_rates(void){ +    const fs_path mb_path = "/mboards/0"; +    _tree->access<double>(mb_path / "tick_rate").update(); + +    //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").update(); +    } +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +        _tree->access<double>(mb_path / "tx_dsps" / name / "rate" / "value").update(); +    } +} + +void b100_impl::update_tick_rate(const double rate){ +    _io_impl->tick_rate = rate; + +    //update the tick rate on all existing streamers -> thread safe +    for (size_t i = 0; i < _rx_streamers.size(); i++){ +        boost::shared_ptr<sph::recv_packet_streamer> my_streamer = +            boost::dynamic_pointer_cast<sph::recv_packet_streamer>(_rx_streamers[i].lock()); +        if (my_streamer.get() == NULL) continue; +        my_streamer->set_tick_rate(rate); +    } +    for (size_t i = 0; i < _tx_streamers.size(); i++){ +        boost::shared_ptr<sph::send_packet_streamer> my_streamer = +            boost::dynamic_pointer_cast<sph::send_packet_streamer>(_tx_streamers[i].lock()); +        if (my_streamer.get() == NULL) continue; +        my_streamer->set_tick_rate(rate); +    } +} + +void b100_impl::update_rx_samp_rate(const size_t dspno, const double rate){ +    boost::shared_ptr<sph::recv_packet_streamer> my_streamer = +        boost::dynamic_pointer_cast<sph::recv_packet_streamer>(_rx_streamers[dspno].lock()); +    if (my_streamer.get() == NULL) return; + +    my_streamer->set_samp_rate(rate); +    const double adj = _rx_dsps[dspno]->get_scaling_adjustment(); +    my_streamer->set_scale_factor(adj); +} + +void b100_impl::update_tx_samp_rate(const size_t dspno, const double rate){ +    boost::shared_ptr<sph::send_packet_streamer> my_streamer = +        boost::dynamic_pointer_cast<sph::send_packet_streamer>(_tx_streamers[dspno].lock()); +    if (my_streamer.get() == NULL) return; + +    my_streamer->set_samp_rate(rate); +    const double adj = _tx_dsp->get_scaling_adjustment(); +    my_streamer->set_scale_factor(adj); +} + +void b100_impl::update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){ +    fs_path 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); +} + +void b100_impl::update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){ +    fs_path 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); +} + +/*********************************************************************** + * 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); +} + +/*********************************************************************** + * Receive streamer + **********************************************************************/ +rx_streamer::sptr b100_impl::get_rx_stream(const uhd::stream_args_t &args_){ +    stream_args_t args = args_; + +    //setup defaults for unspecified values +    args.otw_format = args.otw_format.empty()? "sc16" : args.otw_format; +    args.channels = args.channels.empty()? std::vector<size_t>(1, 0) : args.channels; + +    //calculate packet size +    static const size_t hdr_size = 0 +        + vrt::max_if_hdr_words32*sizeof(boost::uint32_t) +        + sizeof(vrt::if_packet_info_t().tlr) //forced to have trailer +        - sizeof(vrt::if_packet_info_t().cid) //no class id ever used +        - sizeof(vrt::if_packet_info_t().tsi) //no int time ever used +    ; +    const size_t bpp = _data_transport->get_recv_frame_size() - hdr_size; +    const size_t bpi = convert::get_bytes_per_item(args.otw_format); +    const size_t spp = unsigned(args.args.cast<double>("spp", bpp/bpi)); + +    //make the new streamer given the samples per packet +    boost::shared_ptr<sph::recv_packet_streamer> my_streamer = boost::make_shared<sph::recv_packet_streamer>(spp); + +    //init some streamer stuff +    my_streamer->resize(args.channels.size()); +    my_streamer->set_vrt_unpacker(&vrt::if_hdr_unpack_le); + +    //set the converter +    uhd::convert::id_type id; +    id.input_format = args.otw_format + "_item32_le"; +    id.num_inputs = 1; +    id.output_format = args.cpu_format; +    id.num_outputs = 1; +    my_streamer->set_converter(id); + +    //bind callbacks for the handler +    for (size_t chan_i = 0; chan_i < args.channels.size(); chan_i++){ +        const size_t dsp = args.channels[chan_i]; +        _rx_dsps[dsp]->set_nsamps_per_packet(spp); //seems to be a good place to set this +        _rx_dsps[dsp]->setup(args); +        my_streamer->set_xport_chan_get_buff(chan_i, boost::bind( +            &recv_packet_demuxer::get_recv_buff, _io_impl->demuxer, dsp, _1 +        ), true /*flush*/); +        my_streamer->set_overflow_handler(chan_i, boost::bind( +            &rx_dsp_core_200::handle_overflow, _rx_dsps[dsp] +        )); +        _rx_streamers[dsp] = my_streamer; //store weak pointer +    } + +    //sets all tick and samp rates on this streamer +    this->update_rates(); + +    return my_streamer; +} + +/*********************************************************************** + * Transmit streamer + **********************************************************************/ +tx_streamer::sptr b100_impl::get_tx_stream(const uhd::stream_args_t &args_){ +    stream_args_t args = args_; + +    //setup defaults for unspecified values +    args.otw_format = args.otw_format.empty()? "sc16" : args.otw_format; +    args.channels = args.channels.empty()? std::vector<size_t>(1, 0) : args.channels; + +    //calculate packet size +    static const size_t hdr_size = 0 +        + vrt::max_if_hdr_words32*sizeof(boost::uint32_t) +        + sizeof(vrt::if_packet_info_t().tlr) //forced to have trailer +        - sizeof(vrt::if_packet_info_t().sid) //no stream id ever used +        - sizeof(vrt::if_packet_info_t().cid) //no class id ever used +        - sizeof(vrt::if_packet_info_t().tsi) //no int time ever used +    ; +    static const size_t bpp = _data_transport->get_send_frame_size() - hdr_size; +    const size_t spp = bpp/convert::get_bytes_per_item(args.otw_format); + +    //make the new streamer given the samples per packet +    boost::shared_ptr<sph::send_packet_streamer> my_streamer = boost::make_shared<sph::send_packet_streamer>(spp); + +    //init some streamer stuff +    my_streamer->resize(args.channels.size()); +    my_streamer->set_vrt_packer(&vrt::if_hdr_pack_le); + +    //set the converter +    uhd::convert::id_type id; +    id.input_format = args.cpu_format; +    id.num_inputs = 1; +    id.output_format = args.otw_format + "_item32_le"; +    id.num_outputs = 1; +    my_streamer->set_converter(id); + +    //bind callbacks for the handler +    for (size_t chan_i = 0; chan_i < args.channels.size(); chan_i++){ +        const size_t dsp = args.channels[chan_i]; +        UHD_ASSERT_THROW(dsp == 0); //always 0 +        _tx_dsp->setup(args); +        my_streamer->set_xport_chan_get_buff(chan_i, boost::bind( +            &zero_copy_if::get_send_buff, _data_transport, _1 +        )); +        _tx_streamers[dsp] = my_streamer; //store weak pointer +    } + +    //sets all tick and samp rates on this streamer +    this->update_rates(); + +    return my_streamer; +} diff --git a/host/lib/usrp/common/CMakeLists.txt b/host/lib/usrp/common/CMakeLists.txt new file mode 100644 index 000000000..9abd34afa --- /dev/null +++ b/host/lib/usrp/common/CMakeLists.txt @@ -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/>. +# + +######################################################################## +# 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 +    ) +ENDIF(ENABLE_USB) + +INCLUDE_DIRECTORIES(${CMAKE_CURRENT_SOURCE_DIR}) + +LIBUHD_APPEND_SOURCES( +    ${CMAKE_CURRENT_SOURCE_DIR}/apply_corrections.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/validate_subdev_spec.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/recv_packet_demuxer.cpp +) diff --git a/host/lib/usrp/common/apply_corrections.cpp b/host/lib/usrp/common/apply_corrections.cpp new file mode 100644 index 000000000..b889266f2 --- /dev/null +++ b/host/lib/usrp/common/apply_corrections.cpp @@ -0,0 +1,180 @@ +// +// 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 "apply_corrections.hpp" +#include <uhd/usrp/dboard_eeprom.hpp> +#include <uhd/utils/paths.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/utils/csv.hpp> +#include <uhd/types/dict.hpp> +#include <boost/filesystem.hpp> +#include <boost/foreach.hpp> +#include <boost/thread/mutex.hpp> +#include <cstdio> +#include <complex> +#include <fstream> + +namespace fs = boost::filesystem; + +boost::mutex corrections_mutex; + +/*********************************************************************** + * Helper routines + **********************************************************************/ +static double linear_interp(double x, double x0, double y0, double x1, double y1){ +    return y0 + (x - x0)*(y1 - y0)/(x1 - x0); +} + +/*********************************************************************** + * FE apply corrections implementation + **********************************************************************/ +struct fe_cal_t{ +    double lo_freq; +    double iq_corr_real; +    double iq_corr_imag; +}; + +static bool fe_cal_comp(fe_cal_t a, fe_cal_t b){ +    return (a.lo_freq < b.lo_freq); +} + +static uhd::dict<std::string, std::vector<fe_cal_t> > fe_cal_cache; + +static std::complex<double> get_fe_correction( +    const std::string &key, const double lo_freq +){ +    const std::vector<fe_cal_t> &datas = fe_cal_cache[key]; +    if (datas.empty()) throw uhd::runtime_error("empty calibration table " + key); + +    //search for lo freq +    size_t lo_index = 0; +    size_t hi_index = datas.size()-1; +    for (size_t i = 0; i < datas.size(); i++){ +        if (datas[i].lo_freq > lo_freq){ +            hi_index = i; +            break; +        } +        lo_index = i; +    } + +    if (lo_index == 0) return std::complex<double>(datas[lo_index].iq_corr_real, datas[lo_index].iq_corr_imag); +    if (hi_index == lo_index) return std::complex<double>(datas[hi_index].iq_corr_real, datas[hi_index].iq_corr_imag); + +    //interpolation time +    return std::complex<double>( +        linear_interp(lo_freq, datas[lo_index].lo_freq, datas[lo_index].iq_corr_real, datas[hi_index].lo_freq, datas[hi_index].iq_corr_real), +        linear_interp(lo_freq, datas[lo_index].lo_freq, datas[lo_index].iq_corr_imag, datas[hi_index].lo_freq, datas[hi_index].iq_corr_imag) +    ); +} + +static void apply_fe_corrections( +    uhd::property_tree::sptr sub_tree, +    const uhd::fs_path &db_path, +    const uhd::fs_path &fe_path, +    const std::string &file_prefix, +    const double lo_freq +){ +    //extract eeprom serial +    const uhd::usrp::dboard_eeprom_t db_eeprom = sub_tree->access<uhd::usrp::dboard_eeprom_t>(db_path).get(); + +    //make the calibration file path +    const fs::path cal_data_path = fs::path(uhd::get_app_path()) / ".uhd" / "cal" / (file_prefix + db_eeprom.serial + ".csv"); +    if (not fs::exists(cal_data_path)) return; + +    //parse csv file or get from cache +    if (not fe_cal_cache.has_key(cal_data_path.string())){ +        std::ifstream cal_data(cal_data_path.string().c_str()); +        const uhd::csv::rows_type rows = uhd::csv::to_rows(cal_data); + +        bool read_data = false, skip_next = false;; +        std::vector<fe_cal_t> datas; +        BOOST_FOREACH(const uhd::csv::row_type &row, rows){ +            if (not read_data and not row.empty() and row[0] == "DATA STARTS HERE"){ +                read_data = true; +                skip_next = true; +                continue; +            } +            if (not read_data) continue; +            if (skip_next){ +                skip_next = false; +                continue; +            } +            fe_cal_t data; +            std::sscanf(row[0].c_str(), "%lf" , &data.lo_freq); +            std::sscanf(row[1].c_str(), "%lf" , &data.iq_corr_real); +            std::sscanf(row[2].c_str(), "%lf" , &data.iq_corr_imag); +            datas.push_back(data); +        } +        std::sort(datas.begin(), datas.end(), fe_cal_comp); +        fe_cal_cache[cal_data_path.string()] = datas; +        UHD_MSG(status) << "Loaded " << cal_data_path.string() << std::endl; + +    } + +    sub_tree->access<std::complex<double> >(fe_path) +        .set(get_fe_correction(cal_data_path.string(), lo_freq)); +} + +/*********************************************************************** + * Wrapper routines with nice try/catch + print + **********************************************************************/ +void uhd::usrp::apply_tx_fe_corrections( +    property_tree::sptr sub_tree, //starts at mboards/x +    const std::string &slot, //name of dboard slot +    const double lo_freq //actual lo freq +){ +    boost::mutex::scoped_lock l(corrections_mutex); +    try{ +        apply_fe_corrections( +            sub_tree, +            "dboards/" + slot + "/tx_eeprom", +            "tx_frontends/" + slot + "/iq_balance/value", +            "tx_iq_cal_v0.2_", +            lo_freq +        ); +        apply_fe_corrections( +            sub_tree, +            "dboards/" + slot + "/tx_eeprom", +            "tx_frontends/" + slot + "/dc_offset/value", +            "tx_dc_cal_v0.2_", +            lo_freq +        ); +    } +    catch(const std::exception &e){ +        UHD_MSG(error) << "Failure in apply_tx_fe_corrections: " << e.what() << std::endl; +    } +} + +void uhd::usrp::apply_rx_fe_corrections( +    property_tree::sptr sub_tree, //starts at mboards/x +    const std::string &slot, //name of dboard slot +    const double lo_freq //actual lo freq +){ +    boost::mutex::scoped_lock l(corrections_mutex); +    try{ +        apply_fe_corrections( +            sub_tree, +            "dboards/" + slot + "/rx_eeprom", +            "rx_frontends/" + slot + "/iq_balance/value", +            "rx_iq_cal_v0.2_", +            lo_freq +        ); +    } +    catch(const std::exception &e){ +        UHD_MSG(error) << "Failure in apply_rx_fe_corrections: " << e.what() << std::endl; +    } +} diff --git a/host/lib/usrp/common/apply_corrections.hpp b/host/lib/usrp/common/apply_corrections.hpp new file mode 100644 index 000000000..c516862d1 --- /dev/null +++ b/host/lib/usrp/common/apply_corrections.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_APPLY_CORRECTIONS_HPP +#define INCLUDED_LIBUHD_USRP_COMMON_APPLY_CORRECTIONS_HPP + +#include <uhd/config.hpp> +#include <uhd/property_tree.hpp> +#include <string> + +namespace uhd{ namespace usrp{ + +    void apply_tx_fe_corrections( +        property_tree::sptr sub_tree, //starts at mboards/x +        const std::string &slot, //name of dboard slot +        const double tx_lo_freq //actual lo freq +    ); + +    void apply_rx_fe_corrections( +        property_tree::sptr sub_tree, //starts at mboards/x +        const std::string &slot, //name of dboard slot +        const double rx_lo_freq //actual lo freq +    ); + +}} //namespace uhd::usrp + +#endif /* INCLUDED_LIBUHD_USRP_COMMON_APPLY_CORRECTIONS_HPP */ diff --git a/host/lib/usrp/common/async_packet_handler.hpp b/host/lib/usrp/common/async_packet_handler.hpp new file mode 100644 index 000000000..fef03483f --- /dev/null +++ b/host/lib/usrp/common/async_packet_handler.hpp @@ -0,0 +1,71 @@ +// +// Copyright 2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_LIBUHD_USRP_COMMON_ASYNC_PACKET_HANDLER_HPP +#define INCLUDED_LIBUHD_USRP_COMMON_ASYNC_PACKET_HANDLER_HPP + +#include <uhd/config.hpp> +#include <uhd/transport/vrt_if_packet.hpp> +#include <uhd/types/metadata.hpp> +#include <uhd/utils/byteswap.hpp> +#include <uhd/utils/msg.hpp> + +namespace uhd{ namespace usrp{ + +    template <typename to_host_type> +    void load_metadata_from_buff( +        const to_host_type &to_host, +        async_metadata_t &metadata, +        const transport::vrt::if_packet_info_t &if_packet_info, +        const boost::uint32_t *vrt_hdr, +        const double tick_rate, +        const size_t channel = 0 +    ){ +        const boost::uint32_t *payload = vrt_hdr + if_packet_info.num_header_words32; + +        //load into metadata +        metadata.channel = channel; +        metadata.has_time_spec = if_packet_info.has_tsf; +        metadata.time_spec = time_spec_t::from_ticks(if_packet_info.tsf, tick_rate); +        metadata.event_code = async_metadata_t::event_code_t(to_host(payload[0]) & 0xff); + +        //load user payload +        for (size_t i = 1; i < if_packet_info.num_payload_words32; i++){ +            if (i-1 == 4) break; //limit of 4 words32 +            metadata.user_payload[i-1] = to_host(payload[i]); +        } +    } + +    UHD_INLINE void standard_async_msg_prints(const async_metadata_t &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 if (metadata.event_code & +            async_metadata_t::EVENT_CODE_TIME_ERROR +        ) UHD_MSG(fastpath) << "L"; +    } + + +}} //namespace uhd::usrp + +#endif /* INCLUDED_LIBUHD_USRP_COMMON_ASYNC_PACKET_HANDLER_HPP */ diff --git a/host/lib/usrp/common/fx2_ctrl.cpp b/host/lib/usrp/common/fx2_ctrl.cpp new file mode 100644 index 000000000..5cc701eb0 --- /dev/null +++ b/host/lib/usrp/common/fx2_ctrl.cpp @@ -0,0 +1,481 @@ +// +// 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 "fx2_ctrl.hpp" +#include "usrp_commands.h" +#include <uhd/utils/msg.hpp> +#include <uhd/exception.hpp> +#include <uhd/transport/usb_control.hpp> +#include <boost/functional/hash.hpp> +#include <boost/thread/thread.hpp> +#include <boost/cstdint.hpp> +#include <fstream> +#include <sstream> +#include <string> +#include <vector> +#include <cstring> + +using namespace uhd; +using namespace uhd::usrp; + +#define FX2_FIRMWARE_LOAD 0xa0 + +static const bool load_img_msg = true; + +typedef boost::uint32_t hash_type; + +/*********************************************************************** + * Helper Functions + **********************************************************************/ +/*! + * Create a file hash + * The hash will be used to identify the loaded firmware and fpga image + * \param filename file used to generate hash value + * \return hash value in a size_t type + */ +static hash_type generate_hash(const char *filename) +{ +    std::ifstream file(filename); +    if (not file){ +        throw uhd::io_error(std::string("cannot open input file ") + filename); +    } + +    size_t hash = 0; + +    char ch; +    while (file.get(ch)) { +        boost::hash_combine(hash, ch); +    } + +    if (not file.eof()){ +        throw uhd::io_error(std::string("file error ") + filename); +    } + +    file.close(); +    return hash_type(hash); +} + + +/*! + * Verify checksum of a Intel HEX record + * \param record a line from an Intel HEX file + * \return true if record is valid, false otherwise + */ +static bool checksum(std::string *record) +{ + +    size_t len = record->length(); +    unsigned int i; +    unsigned char sum = 0; +    unsigned int val; + +    for (i = 1; i < len; i += 2) { +        std::istringstream(record->substr(i, 2)) >> std::hex >> val; +        sum += val; +    } + +    if (sum == 0) +       return true; +    else +       return false; +} + + +/*! + * Parse Intel HEX record + * + * \param record a line from an Intel HEX file + * \param len output length of record + * \param addr output address + * \param type output type + * \param data output data + * \return true if record is sucessfully read, false on error + */ +bool parse_record(std::string *record, unsigned int &len, +                  unsigned int &addr, unsigned int &type, +                  unsigned char* data) +{ +    unsigned int i; +    std::string _data; +    unsigned int val; + +    if (record->substr(0, 1) != ":") +        return false; + +    std::istringstream(record->substr(1, 2)) >> std::hex >> len; +    std::istringstream(record->substr(3, 4)) >> std::hex >> addr; +    std::istringstream(record->substr(7, 2)) >> std::hex >> type; + +    for (i = 0; i < len; i++) { +        std::istringstream(record->substr(9 + 2 * i, 2)) >> std::hex >> val; +        data[i] = (unsigned char) val; +    } + +    return true; +} + + +/*! + * USRP control implementation for device discovery and configuration + */ +class fx2_ctrl_impl : public fx2_ctrl { +public: +    fx2_ctrl_impl(uhd::transport::usb_control::sptr ctrl_transport) +    { +        _ctrl_transport = ctrl_transport; +    } + +    void usrp_fx2_reset(void){ +        unsigned char reset_y = 1; +        unsigned char reset_n = 0; +        usrp_control_write(FX2_FIRMWARE_LOAD, 0xe600, 0, &reset_y, 1); +        usrp_control_write(FX2_FIRMWARE_LOAD, 0xe600, 0, &reset_n, 1); +        //wait for things to settle +        boost::this_thread::sleep(boost::posix_time::milliseconds(2000)); +    } + +    void usrp_load_firmware(std::string filestring, bool force) +    { +        const char *filename = filestring.c_str(); + +        hash_type hash = generate_hash(filename); + +        hash_type loaded_hash; usrp_get_firmware_hash(loaded_hash); + +        if (not force and (hash == loaded_hash)) return; + +        //FIXME: verify types +        unsigned int len; +        unsigned int addr; +        unsigned int type; +        unsigned char data[512]; + +        std::ifstream file; +        file.open(filename, std::ifstream::in); + +        if (!file.good()) { +            throw uhd::io_error("usrp_load_firmware: cannot open firmware input file"); +        } + +        unsigned char reset_y = 1; +        unsigned char reset_n = 0; + +        //hit the reset line +        if (load_img_msg) UHD_MSG(status) << "Loading firmware image: " << filestring << "..." << std::flush; +        usrp_control_write(FX2_FIRMWARE_LOAD, 0xe600, 0, &reset_y, 1); + +        while (!file.eof()) { +           std::string record; +           file >> record; + +            //check for valid record +            if (not checksum(&record) or not parse_record(&record, len, addr, type, data)) { +                throw uhd::io_error("usrp_load_firmware: bad record checksum"); +            } + +            //type 0x00 is data +            if (type == 0x00) { +                int ret = usrp_control_write(FX2_FIRMWARE_LOAD, addr, 0, data, len); +                if (ret < 0) throw uhd::io_error("usrp_load_firmware: usrp_control_write failed"); +            } +            //type 0x01 is end +            else if (type == 0x01) { +                usrp_set_firmware_hash(hash); //set hash before reset +                usrp_control_write(FX2_FIRMWARE_LOAD, 0xe600, 0, &reset_n, 1); +                file.close(); + +                //wait for things to settle +                boost::this_thread::sleep(boost::posix_time::milliseconds(1000)); +                if (load_img_msg) UHD_MSG(status) << " done" << std::endl; +                return; +            } +            //type anything else is unhandled +            else { +                throw uhd::io_error("usrp_load_firmware: unsupported record"); +            } +        } + +        //file did not end +        throw uhd::io_error("usrp_load_firmware: bad record"); +    } + +    void usrp_init(void){ +        //disable +        usrp_rx_enable(false); +        usrp_tx_enable(false); + +        //toggle resets +        usrp_rx_reset(true); +        usrp_tx_reset(true); +        usrp_rx_reset(false); +        usrp_tx_reset(false); +    } + +    void usrp_load_fpga(std::string filestring) +    { +        const char *filename = filestring.c_str(); + +        hash_type hash = generate_hash(filename); + +        hash_type loaded_hash; usrp_get_fpga_hash(loaded_hash); + +        if (hash == loaded_hash) return; +        const int ep0_size = 64; +        unsigned char buf[ep0_size]; + +        if (load_img_msg) UHD_MSG(status) << "Loading FPGA image: " << filestring << "..." << std::flush; +        std::ifstream file; +        file.open(filename, std::ios::in | std::ios::binary); +        if (not file.good()) { +            throw uhd::io_error("usrp_load_fpga: cannot open fpga input file"); +        } + +        usrp_fpga_reset(true); //holding the fpga in reset while loading + +        if (usrp_control_write_cmd(VRQ_FPGA_LOAD, 0, FL_BEGIN) < 0) { +            throw uhd::io_error("usrp_load_fpga: fpga load error"); +        } + +        while (not file.eof()) { +            file.read((char *)buf, sizeof(buf)); +            const std::streamsize n = file.gcount(); +            if(n == 0) continue; +            int ret = usrp_control_write(VRQ_FPGA_LOAD, 0, FL_XFER, buf, boost::uint16_t(n)); +            if (ret < 0 or std::streamsize(ret) != n) { +                throw uhd::io_error("usrp_load_fpga: fpga load error"); +            } +        } + +        if (usrp_control_write_cmd(VRQ_FPGA_LOAD, 0, FL_END) < 0) { +            throw uhd::io_error("usrp_load_fpga: fpga load error"); +        } + +        usrp_set_fpga_hash(hash); + +        usrp_fpga_reset(false); //done loading, take fpga out of reset + +        file.close(); +        if (load_img_msg) UHD_MSG(status) << " done" << std::endl; +    } + +    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; + +        unsigned int addr; +        unsigned char data[256]; +        unsigned char sendbuf[17]; + +        std::ifstream file; +        file.open(filename, std::ifstream::in); + +        if (not file.good()) { +            throw uhd::io_error("usrp_load_eeprom: cannot open EEPROM input file"); +        } + +        file.read((char *)data, 256); +        std::streamsize len = file.gcount(); + +        if(len == 256) { +            throw uhd::io_error("usrp_load_eeprom: image size too large"); +        } + +        const int pagesize = 16; +        addr = 0; +        while(len > 0) { +            sendbuf[0] = addr; +            memcpy(sendbuf+1, &data[addr], len > pagesize ? pagesize : size_t(len)); +            int ret = usrp_i2c_write(i2c_addr, sendbuf, (len > pagesize ? pagesize : size_t(len))+1); +            if (ret < 0) { +                throw uhd::io_error("usrp_load_eeprom: usrp_i2c_write failed"); +            } +            addr += pagesize; +            len -= pagesize; +            boost::this_thread::sleep(boost::posix_time::milliseconds(100)); +        } +        file.close(); +        if (load_img_msg) UHD_MSG(status) << " done" << std::endl; +    } + + +    void usrp_set_led(int led_num, bool on) +    { +        UHD_ASSERT_THROW(usrp_control_write_cmd(VRQ_SET_LED, on, led_num) >= 0); +    } + + +    void usrp_get_firmware_hash(hash_type &hash) +    { +        UHD_ASSERT_THROW(usrp_control_read(0xa0, USRP_HASH_SLOT_0_ADDR, 0, +                                 (unsigned char*) &hash, sizeof(hash)) >= 0); +    } + + +    void usrp_set_firmware_hash(hash_type hash) +    { +        UHD_ASSERT_THROW(usrp_control_write(0xa0, USRP_HASH_SLOT_0_ADDR, 0, +                                  (unsigned char*) &hash, sizeof(hash)) >= 0); + +    } + + +    void usrp_get_fpga_hash(hash_type &hash) +    { +        UHD_ASSERT_THROW(usrp_control_read(0xa0, USRP_HASH_SLOT_1_ADDR, 0, +                                 (unsigned char*) &hash, sizeof(hash)) >= 0); +    } + + +    void usrp_set_fpga_hash(hash_type hash) +    { +        UHD_ASSERT_THROW(usrp_control_write(0xa0, USRP_HASH_SLOT_1_ADDR, 0, +                                  (unsigned char*) &hash, sizeof(hash)) >= 0); +    } + +    void usrp_tx_enable(bool on) +    { +        UHD_ASSERT_THROW(usrp_control_write_cmd(VRQ_FPGA_SET_TX_ENABLE, on, 0) >= 0); +    } + + +    void usrp_rx_enable(bool on) +    { +        UHD_ASSERT_THROW(usrp_control_write_cmd(VRQ_FPGA_SET_RX_ENABLE, on, 0) >= 0); +    } + + +    void usrp_tx_reset(bool on) +    { +        UHD_ASSERT_THROW(usrp_control_write_cmd(VRQ_FPGA_SET_TX_RESET, on, 0) >= 0); +    } + + +    void usrp_rx_reset(bool on) +    { +        UHD_ASSERT_THROW(usrp_control_write_cmd(VRQ_FPGA_SET_RX_RESET, on, 0) >= 0); +    } + +    void usrp_fpga_reset(bool on) +    { +        UHD_ASSERT_THROW(usrp_control_write_cmd(VRQ_FPGA_SET_RESET, on, 0) >= 0); +    } + +    int usrp_control_write(boost::uint8_t request, +                           boost::uint16_t value, +                           boost::uint16_t index, +                           unsigned char *buff, +                           boost::uint16_t length) +    { +        return _ctrl_transport->submit(VRT_VENDOR_OUT,     // bmReqeustType +                                       request,            // bRequest +                                       value,              // wValue +                                       index,              // wIndex +                                       buff,               // data +                                       length);            // wLength +    } + + +    int usrp_control_read(boost::uint8_t request, +                          boost::uint16_t value, +                          boost::uint16_t index, +                          unsigned char *buff, +                          boost::uint16_t length) +    { +        return _ctrl_transport->submit(VRT_VENDOR_IN,      // bmReqeustType +                                       request,            // bRequest +                                       value,              // wValue +                                       index,              // wIndex +                                       buff,               // data +                                       length);            // wLength +    } + + +    int usrp_control_write_cmd(boost::uint8_t request, boost::uint16_t value, boost::uint16_t index) +    { +        return usrp_control_write(request, value, index, 0, 0); +    } + +    void write_eeprom( +        boost::uint8_t addr, +        boost::uint8_t offset, +        const byte_vector_t &bytes +    ){ +        byte_vector_t bytes_with_cmd(bytes.size() + 1); +        bytes_with_cmd[0] = offset; +        std::copy(bytes.begin(), bytes.end(), &bytes_with_cmd[1]); +        this->write_i2c(addr, bytes_with_cmd); +    } + +    byte_vector_t read_eeprom( +        boost::uint8_t addr, +        boost::uint8_t offset, +        size_t num_bytes +    ){ +        this->write_i2c(addr, byte_vector_t(1, offset)); +        return this->read_i2c(addr, num_bytes); +    } + +    int usrp_i2c_write(boost::uint16_t i2c_addr, unsigned char *buf, boost::uint16_t len) +    { +        return usrp_control_write(VRQ_I2C_WRITE, i2c_addr, 0, buf, len); +    } + +    int usrp_i2c_read(boost::uint16_t i2c_addr, unsigned char *buf, boost::uint16_t len) +    { +        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); + +        int ret = this->usrp_i2c_write(addr, (unsigned char *)&bytes.front(), 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); + +      byte_vector_t bytes(num_bytes); +      int ret = this->usrp_i2c_read(addr, (unsigned char *)&bytes.front(), num_bytes); + +      if (iface_debug && ((ret < 0) || (unsigned)ret < (num_bytes))) +          uhd::runtime_error("USRP: failed i2c read"); + +      return bytes; +    } + + +private: +    uhd::transport::usb_control::sptr _ctrl_transport; +}; + +/*********************************************************************** + * Public make function for fx2_ctrl interface + **********************************************************************/ +fx2_ctrl::sptr fx2_ctrl::make(uhd::transport::usb_control::sptr ctrl_transport){ +    return sptr(new fx2_ctrl_impl(ctrl_transport)); +} + diff --git a/host/lib/usrp/common/fx2_ctrl.hpp b/host/lib/usrp/common/fx2_ctrl.hpp new file mode 100644 index 000000000..f2e060862 --- /dev/null +++ b/host/lib/usrp/common/fx2_ctrl.hpp @@ -0,0 +1,129 @@ +// +// 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_LIBUHD_USRP_COMMON_FX2_CTRL_HPP +#define INCLUDED_LIBUHD_USRP_COMMON_FX2_CTRL_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, public uhd::i2c_iface{ +public: +    typedef boost::shared_ptr<fx2_ctrl> sptr; + +    /*! +     * Make a usrp control object from a control transport +     * \param ctrl_transport a USB control transport +     * \return a new usrp control object +     */ +    static sptr make(uhd::transport::usb_control::sptr ctrl_transport); + +    //! Call init after the fpga is loaded +    virtual void usrp_init(void) = 0; + +    //! For emergency situations +    virtual void usrp_fx2_reset(void) = 0; + +    /*! +     * Load firmware in Intel HEX Format onto device  +     * \param filename name of firmware file +     * \param force reload firmware if already loaded +     */ +    virtual void usrp_load_firmware(std::string filename, +                                   bool force = false) = 0; + +    /*! +     * Load fpga file onto usrp  +     * \param filename name of fpga image  +     */ +    virtual void usrp_load_fpga(std::string filename) = 0; + +    /*! +     * Load USB descriptor file in Intel HEX format into EEPROM +     * \param filename name of EEPROM image +     */ +    virtual void usrp_load_eeprom(std::string filestring) = 0; +     +    /*! +     * Submit an IN transfer  +     * \param request device specific request  +     * \param value device specific field +     * \param index device specific field +     * \param buff buffer to place data +     * \return number of bytes read or error  +     */ +    virtual int usrp_control_read(boost::uint8_t request, +                                  boost::uint16_t value, +                                  boost::uint16_t index, +                                  unsigned char *buff, +                                  boost::uint16_t length) = 0; + +    /*! +     * Submit an OUT transfer  +     * \param request device specific request  +     * \param value device specific field +     * \param index device specific field +     * \param buff buffer of data to be sent  +     * \return number of bytes written or error  +     */ +    virtual int usrp_control_write(boost::uint8_t request, +                                   boost::uint16_t value, +                                   boost::uint16_t index, +                                   unsigned char *buff, +                                   boost::uint16_t length) = 0; + +    /*! +     * Perform an I2C write +     * \param i2c_addr I2C device address +     * \param buf data to be written  +     * \param len length of data in bytes +     * \return number of bytes written or error  +     */ + +    virtual int usrp_i2c_write(boost::uint16_t i2c_addr, +                               unsigned char *buf,  +                               boost::uint16_t len) = 0; + +    /*! +     * Perform an I2C read +     * \param i2c_addr I2C device address +     * \param buf data to be read  +     * \param len length of data in bytes +     * \return number of bytes read or error  +     */ + +    virtual int usrp_i2c_read(boost::uint16_t i2c_addr, +                               unsigned char *buf,  +                               boost::uint16_t len) = 0; + +    //! enable/disable the rx path +    virtual void usrp_rx_enable(bool on) = 0; + +    //! enable/disable the tx path +    virtual void usrp_tx_enable(bool on) = 0; + +    //! reset the fpga +    virtual void usrp_fpga_reset(bool on) = 0; +}; + +}} //namespace uhd::usrp + +#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..f2cfe3bb0 --- /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 unknown 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..3192b0774 --- /dev/null +++ b/host/lib/usrp/cores/CMakeLists.txt @@ -0,0 +1,35 @@ +# +# Copyright 2011-2012 Ettus Research LLC +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# 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}/gpio_core_200.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/i2c_core_100.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/i2c_core_200.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 +    ${CMAKE_CURRENT_SOURCE_DIR}/user_settings_core_200.cpp +) diff --git a/host/lib/usrp/cores/gpio_core_200.cpp b/host/lib/usrp/cores/gpio_core_200.cpp new file mode 100644 index 000000000..cdab70b8d --- /dev/null +++ b/host/lib/usrp/cores/gpio_core_200.cpp @@ -0,0 +1,106 @@ +// +// 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 "gpio_core_200.hpp" +#include <uhd/types/dict.hpp> + +#define REG_GPIO_IDLE          _base + 0 +#define REG_GPIO_RX_ONLY       _base + 4 +#define REG_GPIO_TX_ONLY       _base + 8 +#define REG_GPIO_BOTH          _base + 12 +#define REG_GPIO_DDR           _base + 16 + +using namespace uhd; +using namespace usrp; + +class gpio_core_200_impl : public gpio_core_200{ +public: +    gpio_core_200_impl(wb_iface::sptr iface, const size_t base, const size_t rb_addr): +        _iface(iface), _base(base), _rb_addr(rb_addr) { /* NOP */ } + +    void set_pin_ctrl(const unit_t unit, const boost::uint16_t value){ +        _pin_ctrl[unit] = value; //shadow +        this->update(); //full update +    } + +    void set_atr_reg(const unit_t unit, const atr_reg_t atr, const boost::uint16_t value){ +        _atr_regs[unit][atr] = value;  //shadow +        this->update(); //full update +    } + +    void set_gpio_ddr(const unit_t unit, const boost::uint16_t value){ +        _gpio_ddr[unit] = value; //shadow +        _iface->poke32(REG_GPIO_DDR, //update the 32 bit register +            (boost::uint32_t(_gpio_ddr[dboard_iface::UNIT_RX]) << unit2shit(dboard_iface::UNIT_RX)) | +            (boost::uint32_t(_gpio_ddr[dboard_iface::UNIT_TX]) << unit2shit(dboard_iface::UNIT_TX)) +        ); +    } + +    void set_gpio_out(const unit_t unit, const boost::uint16_t value){ +        _gpio_out[unit] = value; //shadow +        this->update(); //full update +    } + +    boost::uint16_t read_gpio(const unit_t unit){ +        return boost::uint16_t(_iface->peek32(_rb_addr) >> unit2shit(unit)); +    } + +private: +    wb_iface::sptr _iface; +    const size_t _base; +    const size_t _rb_addr; +    uhd::dict<size_t, boost::uint32_t> _update_cache; + +    uhd::dict<unit_t, boost::uint16_t> _pin_ctrl, _gpio_out, _gpio_ddr; +    uhd::dict<unit_t, uhd::dict<atr_reg_t, boost::uint16_t> > _atr_regs; + +    unsigned unit2shit(const unit_t unit){ +        return (unit == dboard_iface::UNIT_RX)? 0 : 16; +    } + +    void update(void){ +        this->update(dboard_iface::ATR_REG_IDLE, REG_GPIO_IDLE); +        this->update(dboard_iface::ATR_REG_TX_ONLY, REG_GPIO_TX_ONLY); +        this->update(dboard_iface::ATR_REG_RX_ONLY, REG_GPIO_RX_ONLY); +        this->update(dboard_iface::ATR_REG_FULL_DUPLEX, REG_GPIO_BOTH); +    } + +    void update(const atr_reg_t atr, const size_t addr){ +        const boost::uint32_t atr_val = +            (boost::uint32_t(_atr_regs[dboard_iface::UNIT_RX][atr]) << unit2shit(dboard_iface::UNIT_RX)) | +            (boost::uint32_t(_atr_regs[dboard_iface::UNIT_TX][atr]) << unit2shit(dboard_iface::UNIT_TX)); + +        const boost::uint32_t gpio_val = +            (boost::uint32_t(_gpio_out[dboard_iface::UNIT_RX]) << unit2shit(dboard_iface::UNIT_RX)) | +            (boost::uint32_t(_gpio_out[dboard_iface::UNIT_TX]) << unit2shit(dboard_iface::UNIT_TX)); + +        const boost::uint32_t ctrl = +            (boost::uint32_t(_pin_ctrl[dboard_iface::UNIT_RX]) << unit2shit(dboard_iface::UNIT_RX)) | +            (boost::uint32_t(_pin_ctrl[dboard_iface::UNIT_TX]) << unit2shit(dboard_iface::UNIT_TX)); +        const boost::uint32_t val = (ctrl & atr_val) | ((~ctrl) & gpio_val); +        if (not _update_cache.has_key(addr) or _update_cache[addr] != val) +        { +            _iface->poke32(addr, val); +        } +        _update_cache[addr] = val; +    } + +}; + +gpio_core_200::sptr gpio_core_200::make(wb_iface::sptr iface, const size_t base, const size_t rb_addr){ +    return sptr(new gpio_core_200_impl(iface, base, rb_addr)); +} diff --git a/host/lib/usrp/cores/gpio_core_200.hpp b/host/lib/usrp/cores/gpio_core_200.hpp new file mode 100644 index 000000000..278575874 --- /dev/null +++ b/host/lib/usrp/cores/gpio_core_200.hpp @@ -0,0 +1,52 @@ +// +// 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_GPIO_CORE_200_HPP +#define INCLUDED_LIBUHD_USRP_GPIO_CORE_200_HPP + +#include <uhd/config.hpp> +#include <uhd/usrp/dboard_iface.hpp> +#include <boost/cstdint.hpp> +#include <boost/utility.hpp> +#include <boost/shared_ptr.hpp> +#include "wb_iface.hpp" + +class gpio_core_200 : boost::noncopyable{ +public: +    typedef boost::shared_ptr<gpio_core_200> sptr; + +    typedef uhd::usrp::dboard_iface::unit_t unit_t; +    typedef uhd::usrp::dboard_iface::atr_reg_t atr_reg_t; + +    //! makes a new GPIO core from iface and slave base +    static sptr make(wb_iface::sptr iface, const size_t base, const size_t rb_addr); + +    //! 1 = ATR +    virtual void set_pin_ctrl(const unit_t unit, const boost::uint16_t value) = 0; + +    virtual void set_atr_reg(const unit_t unit, const atr_reg_t atr, const boost::uint16_t value) = 0; + +    //! 1 = OUTPUT +    virtual void set_gpio_ddr(const unit_t unit, const boost::uint16_t value) = 0; + +    virtual void set_gpio_out(const unit_t unit, const boost::uint16_t value) = 0; + +    virtual boost::uint16_t read_gpio(const unit_t unit) = 0; + +}; + +#endif /* INCLUDED_LIBUHD_USRP_GPIO_CORE_200_HPP */ 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..ceeb3f518 --- /dev/null +++ b/host/lib/usrp/cores/i2c_core_100.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 "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){ +            /* NOP */ +        } + +        _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/i2c_core_200.cpp b/host/lib/usrp/cores/i2c_core_200.cpp new file mode 100644 index 000000000..1b882c54a --- /dev/null +++ b/host/lib/usrp/cores/i2c_core_200.cpp @@ -0,0 +1,158 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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_200.hpp" +#include <uhd/exception.hpp> +#include <uhd/utils/msg.hpp> +#include <boost/thread/thread.hpp> //sleep +#include <boost/thread/mutex.hpp> + +#define REG_I2C_WR_PRESCALER_LO (1 << 3) | 0 +#define REG_I2C_WR_PRESCALER_HI (1 << 3) | 1 +#define REG_I2C_WR_CTRL         (1 << 3) | 2 +#define REG_I2C_WR_DATA         (1 << 3) | 3 +#define REG_I2C_WR_CMD          (1 << 3) | 4 +#define REG_I2C_RD_DATA         (0 << 3) | 3 +#define REG_I2C_RD_ST           (0 << 3) | 4 + +// +// 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_200_impl : public i2c_core_200{ +public: +    i2c_core_200_impl(wb_iface::sptr iface, const size_t base, const size_t readback): +        _iface(iface), _base(base), _readback(readback) +    { +        //init I2C FPGA interface. +        this->poke(REG_I2C_WR_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; +        this->poke(REG_I2C_WR_PRESCALER_LO, prescaler & 0xFF); +        this->poke(REG_I2C_WR_PRESCALER_HI, (prescaler >> 8) & 0xFF); +        this->poke(REG_I2C_WR_CTRL, I2C_CTRL_EN); //enable I2C core +    } + +    void write_i2c( +        boost::uint8_t addr, +        const byte_vector_t &bytes +    ){ +        this->poke(REG_I2C_WR_DATA, (addr << 1) | 0); //addr and read bit (0) +        this->poke(REG_I2C_WR_CMD, I2C_CMD_WR | I2C_CMD_START | (bytes.size() == 0 ? I2C_CMD_STOP : 0)); + +        //wait for previous transfer to complete +        if (not wait_chk_ack()) { +            this->poke(REG_I2C_WR_CMD, I2C_CMD_STOP); +            return; +        } + +        for (size_t i = 0; i < bytes.size(); i++) { +            this->poke(REG_I2C_WR_DATA, bytes[i]); +            this->poke(REG_I2C_WR_CMD, I2C_CMD_WR | ((i == (bytes.size() - 1)) ? I2C_CMD_STOP : 0)); +            if(!wait_chk_ack()) { +                this->poke(REG_I2C_WR_CMD, 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 (this->peek(REG_I2C_RD_ST) & I2C_ST_BUSY){ +            /* NOP */ +        } + +        this->poke(REG_I2C_WR_DATA, (addr << 1) | 1); //addr and read bit (1) +        this->poke(REG_I2C_WR_CMD, I2C_CMD_WR | I2C_CMD_START); +        //wait for previous transfer to complete +        if (not wait_chk_ack()) { +            this->poke(REG_I2C_WR_CMD, I2C_CMD_STOP); +        } +        for (size_t i = 0; i < num_bytes; i++) { +            this->poke(REG_I2C_WR_CMD, I2C_CMD_RD | ((num_bytes == i+1) ? (I2C_CMD_STOP | I2C_CMD_NACK) : 0)); +            i2c_wait(); +            bytes.push_back(this->peek(REG_I2C_RD_DATA)); +        } +        return bytes; +    } + +private: +    void i2c_wait(void) { +        for (size_t i = 0; i < 100; i++){ +            if ((this->peek(REG_I2C_RD_ST) & I2C_ST_TIP) == 0) return; +            boost::this_thread::sleep(boost::posix_time::milliseconds(1)); +        } +        UHD_MSG(error) << "i2c_core_200: i2c_wait timeout" << std::endl; +    } + +    bool wait_chk_ack(void){ +        i2c_wait(); +        return (this->peek(REG_I2C_RD_ST) & I2C_ST_RXACK) == 0; +    } + +    void poke(const size_t what, const boost::uint8_t cmd) +    { +        boost::mutex::scoped_lock lock(_mutex); +        _iface->poke32(_base, (what << 8) | cmd); +    } + +    boost::uint8_t peek(const size_t what) +    { +        boost::mutex::scoped_lock lock(_mutex); +        _iface->poke32(_base, what << 8); +        return boost::uint8_t(_iface->peek32(_readback)); +    } + +    wb_iface::sptr _iface; +    const size_t _base; +    const size_t _readback; +    boost::mutex _mutex; +}; + +i2c_core_200::sptr i2c_core_200::make(wb_iface::sptr iface, const size_t base, const size_t readback){ +    return sptr(new i2c_core_200_impl(iface, base, readback)); +} diff --git a/host/lib/usrp/cores/i2c_core_200.hpp b/host/lib/usrp/cores/i2c_core_200.hpp new file mode 100644 index 000000000..508855985 --- /dev/null +++ b/host/lib/usrp/cores/i2c_core_200.hpp @@ -0,0 +1,35 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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_200_HPP +#define INCLUDED_LIBUHD_USRP_I2C_CORE_200_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_200 : boost::noncopyable, public uhd::i2c_iface{ +public: +    typedef boost::shared_ptr<i2c_core_200> sptr; + +    //! makes a new i2c core from iface and slave base +    static sptr make(wb_iface::sptr iface, const size_t base, const size_t readback); +}; + +#endif /* INCLUDED_LIBUHD_USRP_I2C_CORE_200_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..a89405039 --- /dev/null +++ b/host/lib/usrp/cores/rx_dsp_core_200.cpp @@ -0,0 +1,270 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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/msg.hpp> +#include <uhd/utils/safe_call.hpp> +#include <uhd/utils/algorithm.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/thread/thread.hpp> //thread sleep +#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 +#define REG_DSP_RX_SCALE_IQ   _dsp_base + 4 +#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_HI        _ctrl_base + 4 +#define REG_RX_CTRL_TIME_LO        _ctrl_base + 8 +#define REG_RX_CTRL_FORMAT         _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 + +template <class T> T ceil_log2(T num){ +    return std::ceil(std::log(num)/std::log(T(2))); +} + +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), _sid(sid) +    { +        //init to something so update method has reasonable defaults +        _scaling_adjustment = 1.0; +        _dsp_extra_scaling = 1.0; + +        //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); +            boost::this_thread::sleep(boost::posix_time::milliseconds(10)); //lets lingering pkt propagate +        } + +        this->clear(); +    } + +    ~rx_dsp_core_200_impl(void) +    { +        UHD_SAFE_CALL +        ( +            //shutdown any possible streaming +            this->clear(); +        ) +    } + +    void clear(void){ +        _iface->poke32(REG_RX_CTRL_NCHANNELS, 0); //also reset +        _iface->poke32(REG_RX_CTRL_VRT_HDR, 0 +            | (0x1 << 28) //if data with stream id +            | (0x1 << 26) //has trailer +            | (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 <= 0x0fffffff); +        _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, 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, stop +            (stream_cmd_t::STREAM_MODE_START_CONTINUOUS,   inst_t(true,  true,  false, false)) +            (stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS,    inst_t(false, false, false, true)) +            (stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_DONE, inst_t(false, false, true,  false)) +            (stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_MORE, inst_t(false, true,  true,  false)) +        ; + +        //setup the instruction flag values +        bool inst_reload, inst_chain, inst_samps, inst_stop; +        boost::tie(inst_reload, inst_chain, inst_samps, inst_stop) = 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 |= boost::uint32_t((inst_stop)?             1 : 0) << 28; +        cmd_word |= (inst_samps)? stream_cmd.num_samps : ((inst_stop)? 0 : 1); + +        //issue the stream command +        _iface->poke32(REG_RX_CTRL_STREAM_CMD, cmd_word); +        const boost::uint64_t ticks = (stream_cmd.stream_now)? 0 : stream_cmd.time_spec.to_ticks(_tick_rate); +        _iface->poke32(REG_RX_CTRL_TIME_HI, boost::uint32_t(ticks >> 32)); +        _iface->poke32(REG_RX_CTRL_TIME_LO, boost::uint32_t(ticks >> 0)); //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 +        _link_rate = rate/sizeof(boost::uint16_t); //in samps/s (allows for 8sc) +    } + +    uhd::meta_range_t get_host_rates(void){ +        meta_range_t range; +        for (int rate = 512; rate > 256; rate -= 4){ +            range.push_back(range_t(_tick_rate/rate)); +        } +        for (int rate = 256; rate > 128; rate -= 2){ +            range.push_back(range_t(_tick_rate/rate)); +        } +        for (int rate = 128; rate >= int(std::ceil(_tick_rate/_link_rate)); rate -= 1){ +            range.push_back(range_t(_tick_rate/rate)); +        } +        return range; +    } + +    double set_host_rate(const double rate){ +        const size_t decim_rate = boost::math::iround(_tick_rate/this->get_host_rates().clip(rate, true)); +        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)); + +        // Calculate CIC decimation (i.e., without halfband decimators) +        // Calculate closest multiplier constant to reverse gain absent scale multipliers +        const double rate_pow = std::pow(double(decim & 0xff), 4); +        _scaling_adjustment = std::pow(2, ceil_log2(rate_pow))/(1.65*rate_pow); +        this->update_scalar(); + +        return _tick_rate/decim_rate; +    } + +    void update_scalar(void){ +        const double target_scalar = (1 << 16)*_scaling_adjustment/_dsp_extra_scaling; +        const boost::int32_t actual_scalar = boost::math::iround(target_scalar); +        _fxpt_scalar_correction = target_scalar/actual_scalar; //should be small +        _iface->poke32(REG_DSP_RX_SCALE_IQ, actual_scalar); +    } + +    double get_scaling_adjustment(void){ +        return _fxpt_scalar_correction*_host_extra_scaling/32767.; +    } + +    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); +    } + +    void setup(const uhd::stream_args_t &stream_args){ +        if (not stream_args.args.has_key("noclear")) this->clear(); + +        unsigned format_word = 0; +        if (stream_args.otw_format == "sc16"){ +            format_word = 0; +            _dsp_extra_scaling = 1.0; +            _host_extra_scaling = 1.0; +        } +        else if (stream_args.otw_format == "sc8"){ +            format_word = (1 << 0); +            double peak = stream_args.args.cast<double>("peak", 1.0); +            peak = std::max(peak, 1.0/256); +            _host_extra_scaling = peak*256; +            _dsp_extra_scaling = peak*256; +        } +        else throw uhd::value_error("USRP RX cannot handle requested wire format: " + stream_args.otw_format); + +        _host_extra_scaling *= stream_args.args.cast<double>("fullscale", 1.0); + +        this->update_scalar(); + +        _iface->poke32(REG_RX_CTRL_FORMAT, format_word); +    } + +private: +    wb_iface::sptr _iface; +    const size_t _dsp_base, _ctrl_base; +    double _tick_rate, _link_rate; +    bool _continuous_streaming; +    double _scaling_adjustment, _dsp_extra_scaling, _host_extra_scaling, _fxpt_scalar_correction; +    const boost::uint32_t _sid; +}; + +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..b01f751e9 --- /dev/null +++ b/host/lib/usrp/cores/rx_dsp_core_200.hpp @@ -0,0 +1,67 @@ +// +// 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/stream.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 clear(void) = 0; + +    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_host_rates(void) = 0; + +    virtual double get_scaling_adjustment(void) = 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; + +    virtual void setup(const uhd::stream_args_t &stream_args) = 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..1813758da --- /dev/null +++ b/host/lib/usrp/cores/rx_frontend_core_200.cpp @@ -0,0 +1,80 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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 + +#define OFFSET_FIXED (1ul << 31) +#define OFFSET_SET   (1ul << 30) +#define FLAG_MASK (OFFSET_FIXED | OFFSET_SET) + +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_dc_offset_auto(const bool enb){ +        this->set_dc_offset(enb? 0 : OFFSET_FIXED); +    } + +    std::complex<double> set_dc_offset(const std::complex<double> &off){ +        static const double scaler = double(1ul << 29); +        _i_dc_off = boost::math::iround(off.real()*scaler); +        _q_dc_off = boost::math::iround(off.imag()*scaler); + +        this->set_dc_offset(OFFSET_SET | OFFSET_FIXED); + +        return std::complex<double>(_i_dc_off/scaler, _q_dc_off/scaler); +    } + +    void set_dc_offset(const boost::uint32_t flags){ +        _iface->poke32(REG_RX_FE_OFFSET_I, flags | (_i_dc_off & ~FLAG_MASK)); +        _iface->poke32(REG_RX_FE_OFFSET_Q, flags | (_q_dc_off & ~FLAG_MASK)); +    } + +    void set_iq_balance(const std::complex<double> &cor){ +        _iface->poke32(REG_RX_FE_MAG_CORRECTION, fs_to_bits(cor.real(), 18)); +        _iface->poke32(REG_RX_FE_PHASE_CORRECTION, fs_to_bits(cor.imag(), 18)); +    } + +private: +    boost::int32_t _i_dc_off, _q_dc_off; +    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..5755424c8 --- /dev/null +++ b/host/lib/usrp/cores/rx_frontend_core_200.hpp @@ -0,0 +1,44 @@ +// +// 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_dc_offset_auto(const bool enb) = 0; + +    virtual std::complex<double> set_dc_offset(const std::complex<double> &off) = 0; + +    virtual void set_iq_balance(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..11b310362 --- /dev/null +++ b/host/lib/usrp/cores/time64_core_200.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 "time64_core_200.hpp" +#include <uhd/exception.hpp> +#include <uhd/utils/assert_has.hpp> +#include <boost/math/special_functions/round.hpp> + +#define REG_TIME64_TICKS_HI    _base + 0 +#define REG_TIME64_TICKS_LO    _base + 4 +#define REG_TIME64_FLAGS       _base + 8 +#define REG_TIME64_IMM         _base + 12 +#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 enable_gpsdo(void){ +        _sources.push_back("gpsdo"); +    } + +    void set_tick_rate(const double rate){ +        _tick_rate = 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 ticks_hi = _iface->peek32(_readback_bases.rb_hi_now); +            const boost::uint32_t ticks_lo = _iface->peek32(_readback_bases.rb_lo_now); +            if (ticks_hi != _iface->peek32(_readback_bases.rb_hi_now)) continue; +            const boost::uint64_t ticks = (boost::uint64_t(ticks_hi) << 32) | ticks_lo; +            return time_spec_t::from_ticks(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 ticks_hi = _iface->peek32(_readback_bases.rb_hi_pps); +            const boost::uint32_t ticks_lo = _iface->peek32(_readback_bases.rb_lo_pps); +            if (ticks_hi != _iface->peek32(_readback_bases.rb_hi_pps)) continue; +            const boost::uint64_t ticks = (boost::uint64_t(ticks_hi) << 32) | ticks_lo; +            return time_spec_t::from_ticks(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){ +        const boost::uint64_t ticks = time.to_ticks(_tick_rate); +        _iface->poke32(REG_TIME64_TICKS_LO, boost::uint32_t(ticks >> 0)); +        _iface->poke32(REG_TIME64_IMM, FLAG_TIME64_LATCH_NOW); +        _iface->poke32(REG_TIME64_TICKS_HI, boost::uint32_t(ticks >> 32)); //latches all 3 +    } + +    void set_time_next_pps(const uhd::time_spec_t &time){ +        const boost::uint64_t ticks = time.to_ticks(_tick_rate); +        _iface->poke32(REG_TIME64_TICKS_LO, boost::uint32_t(ticks >> 0)); +        _iface->poke32(REG_TIME64_IMM, FLAG_TIME64_LATCH_NEXT_PPS); +        _iface->poke32(REG_TIME64_TICKS_HI, boost::uint32_t(ticks >> 32)); //latches all 3 +    } + +    void set_time_source(const std::string &source){ +        assert_has(_sources, source, "time source"); + +        //setup pps flags +        if (source == "external" or source == "gpsdo"){ +            _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..315f2ba67 --- /dev/null +++ b/host/lib/usrp/cores/time64_core_200.hpp @@ -0,0 +1,63 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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_hi_now, rb_lo_now; +        size_t rb_hi_pps, rb_lo_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 enable_gpsdo(void) = 0; + +    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..2faf7c28b --- /dev/null +++ b/host/lib/usrp/cores/tx_dsp_core_200.cpp @@ -0,0 +1,216 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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/msg.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 <boost/thread/thread.hpp> //sleep +#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_CLEAR           _ctrl_base + 0 +#define REG_TX_CTRL_FORMAT          _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), _sid(sid) +    { +        //init to something so update method has reasonable defaults +        _scaling_adjustment = 1.0; +        _dsp_extra_scaling = 1.0; + +        //init the tx control registers +        this->clear(); +        this->set_underflow_policy("next_packet"); +    } + +    void clear(void){ +        _iface->poke32(REG_TX_CTRL_CLEAR, 1); //reset and flush technique +        boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +        _iface->poke32(REG_TX_CTRL_CLEAR, 0); +        _iface->poke32(REG_TX_CTRL_REPORT_SID, _sid); +    } + +    void set_underflow_policy(const std::string &policy){ +        if (policy == "next_packet"){ +            _iface->poke32(REG_TX_CTRL_POLICY, FLAG_TX_CTRL_POLICY_NEXT_PACKET); +        } +        else if (policy == "next_burst"){ +            _iface->poke32(REG_TX_CTRL_POLICY, FLAG_TX_CTRL_POLICY_NEXT_BURST); +        } +        else throw uhd::value_error("USRP TX cannot handle requested underflow policy: " + policy); +    } + +    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 +        _link_rate = rate/sizeof(boost::uint16_t); //in samps/s (allows for 8sc) +    } + +    uhd::meta_range_t get_host_rates(void){ +        meta_range_t range; +        for (int rate = 512; rate > 256; rate -= 4){ +            range.push_back(range_t(_tick_rate/rate)); +        } +        for (int rate = 256; rate > 128; rate -= 2){ +            range.push_back(range_t(_tick_rate/rate)); +        } +        for (int rate = 128; rate >= int(std::ceil(_tick_rate/_link_rate)); rate -= 1){ +            range.push_back(range_t(_tick_rate/rate)); +        } +        return range; +    } + +    double set_host_rate(const double rate){ +        const size_t interp_rate = boost::math::iround(_tick_rate/this->get_host_rates().clip(rate, true)); +        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 +        const double rate_pow = std::pow(double(interp & 0xff), 3); +        _scaling_adjustment = std::pow(2, ceil_log2(rate_pow))/(1.65*rate_pow); +        this->update_scalar(); + +        return _tick_rate/interp_rate; +    } + +    void update_scalar(void){ +        const double target_scalar = (1 << 17)*_scaling_adjustment/_dsp_extra_scaling; +        const boost::int32_t actual_scalar = boost::math::iround(target_scalar); +        _fxpt_scalar_correction = target_scalar/actual_scalar; //should be small +        _iface->poke32(REG_DSP_TX_SCALE_IQ, actual_scalar); +    } + +    double get_scaling_adjustment(void){ +        return _fxpt_scalar_correction*_host_extra_scaling*32767.; +    } + +    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)); +    } + +    void setup(const uhd::stream_args_t &stream_args){ +        if (not stream_args.args.has_key("noclear")) this->clear(); + +        unsigned format_word = 0; +        if (stream_args.otw_format == "sc16"){ +            format_word = 0; +            _dsp_extra_scaling = 1.0; +            _host_extra_scaling = 1.0; +        } +        else if (stream_args.otw_format == "sc8"){ +            format_word = (1 << 0); +            double peak = stream_args.args.cast<double>("peak", 1.0); +            peak = std::max(peak, 1.0/256); +            _host_extra_scaling = 1.0/peak/256; +            _dsp_extra_scaling = 1.0/peak; +        } +        else throw uhd::value_error("USRP TX cannot handle requested wire format: " + stream_args.otw_format); + +        _host_extra_scaling /= stream_args.args.cast<double>("fullscale", 1.0); + +        this->update_scalar(); + +        _iface->poke32(REG_TX_CTRL_FORMAT, format_word); + +        if (stream_args.args.has_key("underflow_policy")){ +            this->set_underflow_policy(stream_args.args["underflow_policy"]); +        } +    } + +private: +    wb_iface::sptr _iface; +    const size_t _dsp_base, _ctrl_base; +    double _tick_rate, _link_rate; +    double _scaling_adjustment, _dsp_extra_scaling, _host_extra_scaling, _fxpt_scalar_correction; +    const boost::uint32_t _sid; +}; + +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..0e1cfb6bc --- /dev/null +++ b/host/lib/usrp/cores/tx_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_TX_DSP_CORE_200_HPP +#define INCLUDED_LIBUHD_USRP_TX_DSP_CORE_200_HPP + +#include <uhd/config.hpp> +#include <uhd/stream.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 clear(void) = 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_host_rates(void) = 0; + +    virtual double get_scaling_adjustment(void) = 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; + +    virtual void setup(const uhd::stream_args_t &stream_args) = 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..e35874173 --- /dev/null +++ b/host/lib/usrp/cores/tx_frontend_core_200.cpp @@ -0,0 +1,76 @@ +// +// 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]); +    } + +    std::complex<double> set_dc_offset(const std::complex<double> &off){ +        static const double scaler = double(1ul << 23); +        const boost::int32_t i_dc_off = boost::math::iround(off.real()*scaler); +        const boost::int32_t q_dc_off = boost::math::iround(off.imag()*scaler); + +        _iface->poke32(REG_TX_FE_DC_OFFSET_I, i_dc_off); +        _iface->poke32(REG_TX_FE_DC_OFFSET_Q, q_dc_off); + +        return std::complex<double>(i_dc_off/scaler, q_dc_off/scaler); +    } + +    void set_iq_balance(const std::complex<double> &cor){ +        _iface->poke32(REG_TX_FE_MAG_CORRECTION, fs_to_bits(cor.real(), 18)); +        _iface->poke32(REG_TX_FE_PHASE_CORRECTION, fs_to_bits(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..8ee0f3e6d --- /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 std::complex<double> set_dc_offset(const std::complex<double> &off) = 0; + +    virtual void set_iq_balance(const std::complex<double> &cor) = 0; + +}; + +#endif /* INCLUDED_LIBUHD_USRP_RX_FRONTEND_CORE_200_HPP */ diff --git a/host/lib/usrp/cores/user_settings_core_200.cpp b/host/lib/usrp/cores/user_settings_core_200.cpp new file mode 100644 index 000000000..d262631b1 --- /dev/null +++ b/host/lib/usrp/cores/user_settings_core_200.cpp @@ -0,0 +1,43 @@ +// +// Copyright 2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "user_settings_core_200.hpp" + +#define REG_USER_ADDR             _base + 0 +#define REG_USER_DATA             _base + 4 + +class user_settings_core_200_impl : public user_settings_core_200{ +public: +    user_settings_core_200_impl(wb_iface::sptr iface, const size_t base): +        _iface(iface), _base(base) +    { +        //NOP +    } + +    void set_reg(const user_reg_t ®){ +        _iface->poke32(REG_USER_ADDR, reg.first); +        _iface->poke32(REG_USER_DATA, reg.second); +    } + +private: +    wb_iface::sptr _iface; +    const size_t _base; +}; + +user_settings_core_200::sptr user_settings_core_200::make(wb_iface::sptr iface, const size_t base){ +    return sptr(new user_settings_core_200_impl(iface, base)); +} diff --git a/host/lib/usrp/cores/user_settings_core_200.hpp b/host/lib/usrp/cores/user_settings_core_200.hpp new file mode 100644 index 000000000..1f5d13de7 --- /dev/null +++ b/host/lib/usrp/cores/user_settings_core_200.hpp @@ -0,0 +1,36 @@ +// +// Copyright 2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_LIBUHD_USRP_USER_SETTINGS_CORE_200_HPP +#define INCLUDED_LIBUHD_USRP_USER_SETTINGS_CORE_200_HPP + +#include <uhd/config.hpp> +#include <boost/utility.hpp> +#include <boost/shared_ptr.hpp> +#include "wb_iface.hpp" + +class user_settings_core_200 : boost::noncopyable{ +public: +    typedef boost::shared_ptr<user_settings_core_200> sptr; +    typedef std::pair<boost::uint8_t, boost::uint32_t> user_reg_t; + +    static sptr make(wb_iface::sptr iface, const size_t base); + +    virtual void set_reg(const user_reg_t ®) = 0; +}; + +#endif /* INCLUDED_LIBUHD_USRP_USER_SETTINGS_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/CMakeLists.txt b/host/lib/usrp/dboard/CMakeLists.txt new file mode 100644 index 000000000..b000c7f33 --- /dev/null +++ b/host/lib/usrp/dboard/CMakeLists.txt @@ -0,0 +1,40 @@ +# +# 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/>. +# + +######################################################################## +# This file included, use CMake directory variables +######################################################################## + +LIBUHD_APPEND_SOURCES( +    ${CMAKE_CURRENT_SOURCE_DIR}/db_basic_and_lf.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_rfx.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_xcvr2450.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_sbx_common.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_sbx_version3.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_sbx_version4.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_wbx_common.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_wbx_version2.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_wbx_version3.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_wbx_version4.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_wbx_simple.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_dbsrx.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_unknown.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_tvrx.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_dbsrx2.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/db_tvrx2.cpp +) + diff --git a/host/lib/usrp/dboard/db_basic_and_lf.cpp b/host/lib/usrp/dboard/db_basic_and_lf.cpp new file mode 100644 index 000000000..2b30dab52 --- /dev/null +++ b/host/lib/usrp/dboard/db_basic_and_lf.cpp @@ -0,0 +1,209 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include <uhd/types/dict.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/bind.hpp> +#include <boost/format.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +//! provider function for the always zero freq +static double always_zero_freq(void){return 0.0;} + +/*********************************************************************** + * Constants + **********************************************************************/ +static const uhd::dict<std::string, double> subdev_bandwidth_scalar = map_list_of +    ("A", 1.0) +    ("B", 1.0) +    ("AB", 2.0) +    ("BA", 2.0) +; + +/*********************************************************************** + * The basic and lf boards: + *   They share a common class because only the frequency bounds differ. + **********************************************************************/ +class basic_rx : public rx_dboard_base{ +public: +    basic_rx(ctor_args_t args, double max_freq); +    ~basic_rx(void); + +private: +    double _max_freq; +}; + +class basic_tx : public tx_dboard_base{ +public: +    basic_tx(ctor_args_t args, double max_freq); +    ~basic_tx(void); + +private: +    double _max_freq; +}; + +static const uhd::dict<std::string, std::string> sd_name_to_conn = map_list_of +    ("AB", "IQ") +    ("BA", "QI") +    ("A",  "I") +    ("B",  "Q") +; + +/*********************************************************************** + * Register the basic and LF dboards + **********************************************************************/ +static dboard_base::sptr make_basic_rx(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new basic_rx(args, 250e6)); +} + +static dboard_base::sptr make_basic_tx(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new basic_tx(args, 250e6)); +} + +static dboard_base::sptr make_lf_rx(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new basic_rx(args, 32e6)); +} + +static dboard_base::sptr make_lf_tx(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new basic_tx(args, 32e6)); +} + +UHD_STATIC_BLOCK(reg_basic_and_lf_dboards){ +    dboard_manager::register_dboard(0x0000, &make_basic_tx, "Basic TX", sd_name_to_conn.keys()); +    dboard_manager::register_dboard(0x0001, &make_basic_rx, "Basic RX", sd_name_to_conn.keys()); +    dboard_manager::register_dboard(0x000e, &make_lf_tx,    "LF TX",    sd_name_to_conn.keys()); +    dboard_manager::register_dboard(0x000f, &make_lf_rx,    "LF RX",    sd_name_to_conn.keys()); +} + +/*********************************************************************** + * Basic and LF RX dboard + **********************************************************************/ +basic_rx::basic_rx(ctor_args_t args, double max_freq) : rx_dboard_base(args){ +    _max_freq = max_freq; +    //this->get_iface()->set_clock_enabled(dboard_iface::UNIT_RX, true); +     +    //////////////////////////////////////////////////////////////////// +    // Register properties +    //////////////////////////////////////////////////////////////////// +    if(get_rx_id() == 0x0001){ +        this->get_rx_subtree()->create<std::string>("name").set( +            std::string(str(boost::format("BasicRX (%s)") % get_subdev_name() +        ))); +    } +    else{ +        this->get_rx_subtree()->create<std::string>("name").set( +            std::string(str(boost::format("LFRX (%s)") % get_subdev_name() +        ))); +    } + +    this->get_rx_subtree()->create<int>("gains"); //phony property so this dir exists +    this->get_rx_subtree()->create<double>("freq/value") +        .publish(&always_zero_freq); +    this->get_rx_subtree()->create<meta_range_t>("freq/range") +        .set(freq_range_t(-_max_freq, +_max_freq)); +    this->get_rx_subtree()->create<std::string>("antenna/value") +        .set(""); +    this->get_rx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(list_of("")); +    this->get_rx_subtree()->create<int>("sensors"); //phony property so this dir exists +    this->get_rx_subtree()->create<std::string>("connection") +        .set(sd_name_to_conn[get_subdev_name()]); +    this->get_rx_subtree()->create<bool>("enabled") +        .set(true); //always enabled +    this->get_rx_subtree()->create<bool>("use_lo_offset") +        .set(false); +    this->get_rx_subtree()->create<double>("bandwidth/value") +        .set(subdev_bandwidth_scalar[get_subdev_name()]*_max_freq); +    this->get_rx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(subdev_bandwidth_scalar[get_subdev_name()]*_max_freq, subdev_bandwidth_scalar[get_subdev_name()]*_max_freq)); +     +    //disable RX dboard clock by default +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_RX, false); + +    //set GPIOs to output 0x0000 to decrease noise pickup +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, 0x0000); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, 0xFFFF); +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, 0x0000); +} + +basic_rx::~basic_rx(void){ +    /* NOP */ +} + +/*********************************************************************** + * Basic and LF TX dboard + **********************************************************************/ +basic_tx::basic_tx(ctor_args_t args, double max_freq) : tx_dboard_base(args){ +    _max_freq = max_freq; +    //this->get_iface()->set_clock_enabled(dboard_iface::UNIT_TX, true); + +    //////////////////////////////////////////////////////////////////// +    // Register properties +    //////////////////////////////////////////////////////////////////// +    if(get_tx_id() == 0x0000){ +        this->get_tx_subtree()->create<std::string>("name").set( +            std::string(str(boost::format("BasicTX (%s)") % get_subdev_name() +        ))); +    } +    else{ +        this->get_tx_subtree()->create<std::string>("name").set( +            std::string(str(boost::format("LFTX (%s)") % get_subdev_name() +        ))); +    } + +    this->get_tx_subtree()->create<int>("gains"); //phony property so this dir exists +    this->get_tx_subtree()->create<double>("freq/value") +        .publish(&always_zero_freq); +    this->get_tx_subtree()->create<meta_range_t>("freq/range") +        .set(freq_range_t(-_max_freq, +_max_freq)); +    this->get_tx_subtree()->create<std::string>("antenna/value") +        .set(""); +    this->get_tx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(list_of("")); +    this->get_tx_subtree()->create<int>("sensors"); //phony property so this dir exists +    this->get_tx_subtree()->create<std::string>("connection") +        .set(sd_name_to_conn[get_subdev_name()]); +    this->get_tx_subtree()->create<bool>("enabled") +        .set(true); //always enabled +    this->get_tx_subtree()->create<bool>("use_lo_offset") +        .set(false); +    this->get_tx_subtree()->create<double>("bandwidth/value") +        .set(subdev_bandwidth_scalar[get_subdev_name()]*_max_freq); +    this->get_tx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(subdev_bandwidth_scalar[get_subdev_name()]*_max_freq, subdev_bandwidth_scalar[get_subdev_name()]*_max_freq)); +     +    //disable TX dboard clock by default +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_TX, false); + +    //set GPIOs to output 0x0000 to decrease noise pickup +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_TX, 0x0000); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_TX, 0xFFFF); +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_TX, 0x0000); +} + +basic_tx::~basic_tx(void){ +    /* NOP */ +} diff --git a/host/lib/usrp/dboard/db_dbsrx.cpp b/host/lib/usrp/dboard/db_dbsrx.cpp new file mode 100644 index 000000000..b1cee4aa7 --- /dev/null +++ b/host/lib/usrp/dboard/db_dbsrx.cpp @@ -0,0 +1,544 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +// No RX IO Pins Used + +// RX IO Functions + +#include "max2118_regs.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/thread.hpp> +#include <boost/math/special_functions/round.hpp> +#include <utility> +#include <cmath> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +/*********************************************************************** + * The DBSRX constants + **********************************************************************/ +static const freq_range_t dbsrx_freq_range(0.8e9, 2.4e9); + +//Multiplied by 2.0 for conversion to complex bandpass from lowpass +static const freq_range_t dbsrx_bandwidth_range(2.0*4.0e6, 2.0*33.0e6); + +static const freq_range_t dbsrx_pfd_freq_range(0.15e6, 2.01e6); + +static const std::vector<std::string> dbsrx_antennas = list_of("J3"); + +static const uhd::dict<std::string, gain_range_t> dbsrx_gain_ranges = map_list_of +    ("GC1", gain_range_t(0, 56, 0.5)) +    ("GC2", gain_range_t(0, 24, 1)) +; + +static const double usrp1_gpio_clock_rate_limit = 4e6; + +/*********************************************************************** + * The DBSRX dboard class + **********************************************************************/ +class dbsrx : public rx_dboard_base{ +public: +    dbsrx(ctor_args_t args); +    ~dbsrx(void); + +private: +    double _lo_freq; +    double _bandwidth; +    uhd::dict<std::string, double> _gains; +    max2118_write_regs_t _max2118_write_regs; +    max2118_read_regs_t _max2118_read_regs; +    boost::uint8_t _max2118_addr(void){ +        return (this->get_iface()->get_special_props().mangle_i2c_addrs)? 0x65 : 0x67; +    }; + +    double set_lo_freq(double target_freq); +    double set_gain(double gain, const std::string &name); +    double set_bandwidth(double bandwidth); + +    void send_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg){ +        start_reg = boost::uint8_t(uhd::clip(int(start_reg), 0x0, 0x5)); +        stop_reg = boost::uint8_t(uhd::clip(int(stop_reg), 0x0, 0x5)); + +        for(boost::uint8_t start_addr=start_reg; start_addr <= stop_reg; start_addr += sizeof(boost::uint32_t) - 1){ +            int num_bytes = int(stop_reg - start_addr + 1) > int(sizeof(boost::uint32_t)) - 1 ? sizeof(boost::uint32_t) - 1 : stop_reg - start_addr + 1; + +            //create buffer for register data (+1 for start address) +            byte_vector_t regs_vector(num_bytes + 1); + +            //first byte is the address of first register +            regs_vector[0] = start_addr; + +            //get the register data +            for(int i=0; i<num_bytes; i++){ +                regs_vector[1+i] = _max2118_write_regs.get_reg(start_addr+i); +                UHD_LOGV(often) << boost::format( +                    "DBSRX: send reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" +                ) % int(start_addr+i) % int(regs_vector[1+i]) % int(start_addr) % num_bytes << std::endl; +            } + +            //send the data +            this->get_iface()->write_i2c( +                _max2118_addr(), regs_vector +            ); +        } +    } + +    void read_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg){ +        static const boost::uint8_t status_addr = 0x0; +        start_reg = boost::uint8_t(uhd::clip(int(start_reg), 0x0, 0x1)); +        stop_reg = boost::uint8_t(uhd::clip(int(stop_reg), 0x0, 0x1)); + +        for(boost::uint8_t start_addr=start_reg; start_addr <= stop_reg; start_addr += sizeof(boost::uint32_t)){ +            int num_bytes = int(stop_reg - start_addr + 1) > int(sizeof(boost::uint32_t)) ? sizeof(boost::uint32_t) : stop_reg - start_addr + 1; + +            //create buffer for register data +            byte_vector_t regs_vector(num_bytes); + +            //read from i2c +            regs_vector = this->get_iface()->read_i2c( +                _max2118_addr(), num_bytes +            ); + +            for(boost::uint8_t i=0; i < num_bytes; i++){ +                if (i + start_addr >= status_addr){ +                    _max2118_read_regs.set_reg(i + start_addr, regs_vector[i]); +                } +                UHD_LOGV(often) << boost::format( +                    "DBSRX: read reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" +                ) % int(start_addr+i) % int(regs_vector[i]) % int(start_addr) % num_bytes << std::endl; +            } +        } +    } + +    /*! +     * Get the lock detect status of the LO. +     * \return sensor for locked +     */ +    sensor_value_t get_locked(void){ +        read_reg(0x0, 0x0); + +        //mask and return lock detect +        bool locked = 5 >= _max2118_read_regs.adc and _max2118_read_regs.adc >= 2; + +        UHD_LOGV(often) << boost::format( +            "DBSRX: locked %d" +        ) % locked << std::endl; + +        return sensor_value_t("LO", locked, "locked", "unlocked"); +    } +}; + +/*********************************************************************** + * Register the DBSRX dboard + **********************************************************************/ +static dboard_base::sptr make_dbsrx(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new dbsrx(args)); +} + +UHD_STATIC_BLOCK(reg_dbsrx_dboard){ +    //register the factory function for the rx dbid (others version) +    dboard_manager::register_dboard(0x000D, &make_dbsrx, "DBSRX"); +    //register the factory function for the rx dbid (USRP1 version) +    dboard_manager::register_dboard(0x0002, &make_dbsrx, "DBSRX"); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +dbsrx::dbsrx(ctor_args_t args) : rx_dboard_base(args){ +    //warn user about incorrect DBID on USRP1, requires R193 populated +    if (this->get_iface()->get_special_props().soft_clock_divider and this->get_rx_id() == 0x000D) +        UHD_MSG(warning) << boost::format( +                "DBSRX: incorrect dbid\n" +                "Expected dbid 0x0002 and R193\n" +                "found dbid == %d\n" +                "Please see the daughterboard app notes"  +                ) % this->get_rx_id().to_pp_string(); + +    //warn user about incorrect DBID on non-USRP1, requires R194 populated +    if (not this->get_iface()->get_special_props().soft_clock_divider and this->get_rx_id() == 0x0002) +        UHD_MSG(warning) << boost::format( +                "DBSRX: incorrect dbid\n" +                "Expected dbid 0x000D and R194\n" +                "found dbid == %d\n" +                "Please see the daughterboard app notes"  +                ) % this->get_rx_id().to_pp_string(); + +    //send initial register settings +    this->send_reg(0x0, 0x5); + +    //set defaults for LO, gains, and filter bandwidth +    double codec_rate = this->get_iface()->get_codec_rate(dboard_iface::UNIT_RX); +    _bandwidth = 0.8*codec_rate/2.0; // default to anti-alias at different codec_rate + +    //////////////////////////////////////////////////////////////////// +    // Register properties +    //////////////////////////////////////////////////////////////////// +    this->get_rx_subtree()->create<std::string>("name") +        .set("DBSRX"); +    this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&dbsrx::get_locked, this)); +    BOOST_FOREACH(const std::string &name, dbsrx_gain_ranges.keys()){ +        this->get_rx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&dbsrx::set_gain, this, _1, name)) +            .set(dbsrx_gain_ranges[name].start()); +        this->get_rx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(dbsrx_gain_ranges[name]); +    } +    this->get_rx_subtree()->create<double>("freq/value") +        .coerce(boost::bind(&dbsrx::set_lo_freq, this, _1)); +    this->get_rx_subtree()->create<meta_range_t>("freq/range") +        .set(dbsrx_freq_range); +    this->get_rx_subtree()->create<std::string>("antenna/value") +        .set(dbsrx_antennas.at(0)); +    this->get_rx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(dbsrx_antennas); +    this->get_rx_subtree()->create<std::string>("connection") +        .set("IQ"); +    this->get_rx_subtree()->create<bool>("enabled") +        .set(true); //always enabled +    this->get_rx_subtree()->create<bool>("use_lo_offset") +        .set(false); +    this->get_rx_subtree()->create<double>("bandwidth/value") +        .coerce(boost::bind(&dbsrx::set_bandwidth, this, _1)); +    this->get_rx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(dbsrx_bandwidth_range); + +    //enable only the clocks we need +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_RX, true); + +    //set the gpio directions and atr controls (identically) +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, 0x0); // All unused in atr +    if (this->get_iface()->get_special_props().soft_clock_divider){ +        this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, 0x1); // GPIO0 is clock when on USRP1 +    } +    else{ +        this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, 0x0); // All Inputs +    } + +    //now its safe to set inital freq and bw +    this->get_rx_subtree()->access<double>("freq/value") +        .set(dbsrx_freq_range.start()); +    this->get_rx_subtree()->access<double>("bandwidth/value") +        .set(2.0*_bandwidth); //_bandwidth in lowpass, convert to complex bandpass +} + +dbsrx::~dbsrx(void){ +} + + +/*********************************************************************** + * Tuning + **********************************************************************/ +double dbsrx::set_lo_freq(double target_freq){ +    target_freq = dbsrx_freq_range.clip(target_freq); + +    double actual_freq=0.0, pfd_freq=0.0, ref_clock=0.0; +    int R=0, N=0, r=0, m=0; +    bool update_filter_settings = false; +    //choose refclock +    std::vector<double> clock_rates = this->get_iface()->get_clock_rates(dboard_iface::UNIT_RX); +    const double max_clock_rate = uhd::sorted(clock_rates).back(); +    BOOST_FOREACH(ref_clock, uhd::reversed(uhd::sorted(clock_rates))){ +        //USRP1 feeds the DBSRX clock from a FPGA GPIO line. +        //make sure that this clock does not exceed rate limit. +        if (this->get_iface()->get_special_props().soft_clock_divider){ +            if (ref_clock > usrp1_gpio_clock_rate_limit) continue; +        } +        if (ref_clock > 27.0e6) continue; +        if (size_t(max_clock_rate/ref_clock)%2 == 1) continue; //reject asymmetric clocks (odd divisors) + +        //choose m_divider such that filter tuning constraint is met +        m = 31; +        while ((ref_clock/m < 1e6 or ref_clock/m > 2.5e6) and m > 0){ m--; } + +        UHD_LOGV(often) << boost::format( +            "DBSRX: trying ref_clock %f and m_divider %d" +        ) % (ref_clock) % m << std::endl; + +        if (m >= 32) continue; + +        //choose R +        for(r = 0; r <= 6; r += 1) { +            //compute divider from setting +            R = 1 << (r+1); +            UHD_LOGV(often) << boost::format("DBSRX R:%d\n") % R << std::endl; + +            //compute PFD compare frequency = ref_clock/R +            pfd_freq = ref_clock / R; + +            //constrain the PFD frequency to specified range +            if ((pfd_freq < dbsrx_pfd_freq_range.start()) or (pfd_freq > dbsrx_pfd_freq_range.stop())) continue; + +            //compute N +            N = int(std::floor(target_freq/pfd_freq)); + +            //constrain N to specified range +            if ((N < 256) or (N > 32768)) continue; + +            goto done_loop; +        } +    }  + +    done_loop: + +    //Assert because we failed to find a suitable combination of ref_clock, R and N  +    UHD_ASSERT_THROW(ref_clock <= 27.0e6 and ref_clock >= 0.0); +    UHD_ASSERT_THROW(ref_clock/m >= 1e6 and ref_clock/m <= 2.5e6); +    UHD_ASSERT_THROW((pfd_freq >= dbsrx_pfd_freq_range.start()) and (pfd_freq <= dbsrx_pfd_freq_range.stop())); +    UHD_ASSERT_THROW((N >= 256) and (N <= 32768)); + +    UHD_LOGV(often) << boost::format( +        "DBSRX: choose ref_clock (current: %f, new: %f) and m_divider %d" +    ) % (this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX)) % ref_clock % m << std::endl; + +    //if ref_clock or m divider changed, we need to update the filter settings +    if (ref_clock != this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX) or m != _max2118_write_regs.m_divider) update_filter_settings = true; + +    //compute resulting output frequency +    actual_freq = pfd_freq * N; + +    //apply ref_clock, R, and N settings +    this->get_iface()->set_clock_rate(dboard_iface::UNIT_RX, ref_clock); +    ref_clock = this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX); +    _max2118_write_regs.m_divider = m; +    _max2118_write_regs.r_divider = (max2118_write_regs_t::r_divider_t) r; +    _max2118_write_regs.set_n_divider(N); +    _max2118_write_regs.ade_vco_ade_read = max2118_write_regs_t::ADE_VCO_ADE_READ_ENABLED; +     +    //compute prescaler variables +    int scaler = actual_freq > 1125e6 ? 2 : 4; +    _max2118_write_regs.div2 = scaler == 4 ? max2118_write_regs_t::DIV2_DIV4 : max2118_write_regs_t::DIV2_DIV2; + +    UHD_LOGV(often) << boost::format( +        "DBSRX: scaler %d, actual_freq %f MHz, register bit: %d" +    ) % scaler % (actual_freq/1e6) % int(_max2118_write_regs.div2) << std::endl; + +    //compute vco frequency and select vco +    double vco_freq = actual_freq * scaler; +    if (vco_freq < 2433e6) +        _max2118_write_regs.osc_band = 0; +    else if (vco_freq < 2711e6) +        _max2118_write_regs.osc_band = 1; +    else if (vco_freq < 3025e6) +        _max2118_write_regs.osc_band = 2; +    else if (vco_freq < 3341e6) +        _max2118_write_regs.osc_band = 3; +    else if (vco_freq < 3727e6) +        _max2118_write_regs.osc_band = 4; +    else if (vco_freq < 4143e6) +        _max2118_write_regs.osc_band = 5; +    else if (vco_freq < 4493e6) +        _max2118_write_regs.osc_band = 6; +    else +        _max2118_write_regs.osc_band = 7; + +    //send settings over i2c +    send_reg(0x0, 0x4); + +    //check vtune for lock condition +    read_reg(0x0, 0x0); + +    UHD_LOGV(often) << boost::format( +        "DBSRX: initial guess for vco %d, vtune adc %d" +    ) % int(_max2118_write_regs.osc_band) % int(_max2118_read_regs.adc) << std::endl; + +    //if we are out of lock for chosen vco, change vco +    while ((_max2118_read_regs.adc == 0) or (_max2118_read_regs.adc == 7)){ + +        //vtune is too low, try lower frequency vco +        if (_max2118_read_regs.adc == 0){ +            if (_max2118_write_regs.osc_band == 0){ +                UHD_MSG(warning) << boost::format( +                        "DBSRX: Tuning exceeded vco range, _max2118_write_regs.osc_band == %d\n"  +                        ) % int(_max2118_write_regs.osc_band); +                UHD_ASSERT_THROW(_max2118_read_regs.adc != 0); //just to cause a throw +            } +            if (_max2118_write_regs.osc_band <= 0) break; +            _max2118_write_regs.osc_band -= 1; +        } + +        //vtune is too high, try higher frequency vco +        if (_max2118_read_regs.adc == 7){ +            if (_max2118_write_regs.osc_band == 7){ +                UHD_MSG(warning) << boost::format( +                        "DBSRX: Tuning exceeded vco range, _max2118_write_regs.osc_band == %d\n"  +                        ) % int(_max2118_write_regs.osc_band); +                UHD_ASSERT_THROW(_max2118_read_regs.adc != 7); //just to cause a throw +            } +            if (_max2118_write_regs.osc_band >= 7) break; +            _max2118_write_regs.osc_band += 1; +        } + +        UHD_LOGV(often) << boost::format( +            "DBSRX: trying vco %d, vtune adc %d" +        ) % int(_max2118_write_regs.osc_band) % int(_max2118_read_regs.adc) << std::endl; + +        //update vco selection and check vtune +        send_reg(0x2, 0x2); +        read_reg(0x0, 0x0); + +        //allow for setup time before checking condition again +        boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +    } +       +    UHD_LOGV(often) << boost::format( +        "DBSRX: final vco %d, vtune adc %d" +    ) % int(_max2118_write_regs.osc_band) % int(_max2118_read_regs.adc) << std::endl; + +    //select charge pump bias current +    if (_max2118_read_regs.adc <= 2) _max2118_write_regs.cp_current = max2118_write_regs_t::CP_CURRENT_I_CP_100UA; +    else if (_max2118_read_regs.adc >= 5) _max2118_write_regs.cp_current = max2118_write_regs_t::CP_CURRENT_I_CP_400UA; +    else _max2118_write_regs.cp_current = max2118_write_regs_t::CP_CURRENT_I_CP_200UA; +     +    //update charge pump bias current setting +    send_reg(0x2, 0x2); + +    //compute actual tuned frequency +    _lo_freq = this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX) / std::pow(2.0,(1 + _max2118_write_regs.r_divider)) * _max2118_write_regs.get_n_divider(); + +    //debug output of calculated variables +    UHD_LOGV(often) +        << boost::format("DBSRX tune:\n") +        << boost::format("    VCO=%d, CP=%d, PFD Freq=%fMHz\n") % int(_max2118_write_regs.osc_band) % _max2118_write_regs.cp_current % (pfd_freq/1e6) +        << boost::format("    R=%d, N=%f, scaler=%d, div2=%d\n") % R % N % scaler % int(_max2118_write_regs.div2) +        << boost::format("    Ref    Freq=%fMHz\n") % (ref_clock/1e6) +        << boost::format("    Target Freq=%fMHz\n") % (target_freq/1e6) +        << boost::format("    Actual Freq=%fMHz\n") % (_lo_freq/1e6) +        << boost::format("    VCO    Freq=%fMHz\n") % (vco_freq/1e6) +        << std::endl; + +    if (update_filter_settings) set_bandwidth(_bandwidth); +    get_locked(); + +    return _lo_freq; +} + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +/*! + * Convert a requested gain for the GC2 vga into the integer register value. + * The gain passed into the function will be set to the actual value. + * \param gain the requested gain in dB + * \return 5 bit the register value + */ +static int gain_to_gc2_vga_reg(double &gain){ +    int reg = 0; +    gain = dbsrx_gain_ranges["GC2"].clip(gain); + +    // Half dB steps from 0-5dB, 1dB steps from 5-24dB +    if (gain < 5) { +        reg = boost::math::iround(31.0 - gain/0.5); +        gain = double(boost::math::iround(gain) * 0.5); +    } else { +        reg = boost::math::iround(22.0 - (gain - 4.0)); +        gain = double(boost::math::iround(gain)); +    } + +    UHD_LOGV(often) << boost::format( +        "DBSRX GC2 Gain: %f dB, reg: %d" +    ) % gain % reg << std::endl; + +    return reg; +} + +/*! + * Convert a requested gain for the GC1 rf vga into the dac_volts value. + * The gain passed into the function will be set to the actual value. + * \param gain the requested gain in dB + * \return dac voltage value + */ +static double gain_to_gc1_rfvga_dac(double &gain){ +    //clip the input +    gain = dbsrx_gain_ranges["GC1"].clip(gain); + +    //voltage level constants +    static const double max_volts = 1.2, min_volts = 2.7; +    static const double slope = (max_volts-min_volts)/dbsrx_gain_ranges["GC1"].stop(); + +    //calculate the voltage for the aux dac +    double dac_volts = gain*slope + min_volts; + +    UHD_LOGV(often) << boost::format( +        "DBSRX GC1 Gain: %f dB, dac_volts: %f V" +    ) % gain % dac_volts << std::endl; + +    //the actual gain setting +    gain = (dac_volts - min_volts)/slope; + +    return dac_volts; +} + +double dbsrx::set_gain(double gain, const std::string &name){ +    assert_has(dbsrx_gain_ranges.keys(), name, "dbsrx gain name"); +    if (name == "GC2"){ +        _max2118_write_regs.gc2 = gain_to_gc2_vga_reg(gain); +        send_reg(0x5, 0x5); +    } +    else if(name == "GC1"){ +        //write the new voltage to the aux dac +        this->get_iface()->write_aux_dac(dboard_iface::UNIT_RX, dboard_iface::AUX_DAC_A, gain_to_gc1_rfvga_dac(gain)); +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    _gains[name] = gain; + +    return gain; +} + +/*********************************************************************** + * Bandwidth Handling + **********************************************************************/ +double dbsrx::set_bandwidth(double bandwidth){ +    //convert complex bandpass to lowpass bandwidth +    bandwidth = bandwidth/2.0; + +    //clip the input +    bandwidth = dbsrx_bandwidth_range.clip(bandwidth); + +    double ref_clock = this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX); +     +    //NOTE: _max2118_write_regs.m_divider set in set_lo_freq + +    //compute f_dac setting +    _max2118_write_regs.f_dac = uhd::clip<int>(int((((bandwidth*_max2118_write_regs.m_divider)/ref_clock) - 4)/0.145),0,127); + +    //determine actual bandwidth +    _bandwidth = double((ref_clock/(_max2118_write_regs.m_divider))*(4+0.145*_max2118_write_regs.f_dac)); + +    UHD_LOGV(often) << boost::format( +        "DBSRX Filter Bandwidth: %f MHz, m: %d, f_dac: %d\n" +    ) % (_bandwidth/1e6) % int(_max2118_write_regs.m_divider) % int(_max2118_write_regs.f_dac) << std::endl; + +    this->send_reg(0x3, 0x4); + +    //convert lowpass back to complex bandpass bandwidth +    return 2.0*_bandwidth; +} diff --git a/host/lib/usrp/dboard/db_dbsrx2.cpp b/host/lib/usrp/dboard/db_dbsrx2.cpp new file mode 100644 index 000000000..013f3178a --- /dev/null +++ b/host/lib/usrp/dboard/db_dbsrx2.cpp @@ -0,0 +1,379 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +// No RX IO Pins Used + +#include "max2112_regs.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/thread.hpp> +#include <boost/math/special_functions/round.hpp> +#include <utility> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +/*********************************************************************** + * The DBSRX2 constants + **********************************************************************/ +static const freq_range_t dbsrx2_freq_range(0.8e9, 2.4e9); + +//Multiplied by 2.0 for conversion to complex bandpass from lowpass +static const freq_range_t dbsrx2_bandwidth_range(2.0*4.0e6, 2.0*40.0e6); + +static const int dbsrx2_ref_divider = 4; // Hitachi HMC426 divider (U7) + +static const std::vector<std::string> dbsrx2_antennas = list_of("J3"); + +static const uhd::dict<std::string, gain_range_t> dbsrx2_gain_ranges = map_list_of +    ("GC1", gain_range_t(0, 73, 0.05)) +    ("BBG", gain_range_t(0, 15, 1)) +; + +/*********************************************************************** + * The DBSRX2 dboard class + **********************************************************************/ +class dbsrx2 : public rx_dboard_base{ +public: +    dbsrx2(ctor_args_t args); +    ~dbsrx2(void); + +private: +    double _lo_freq; +    double _bandwidth; +    uhd::dict<std::string, double> _gains; +    max2112_write_regs_t _max2112_write_regs; +    max2112_read_regs_t _max2112_read_regs; +    boost::uint8_t _max2112_addr(){ //0x60 or 0x61 depending on which side +        return (this->get_iface()->get_special_props().mangle_i2c_addrs)? 0x60 : 0x61; +    } + +    double set_lo_freq(double target_freq); +    double set_gain(double gain, const std::string &name); +    double set_bandwidth(double bandwidth); + +    void send_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg){ +        start_reg = boost::uint8_t(uhd::clip(int(start_reg), 0x0, 0xB)); +        stop_reg = boost::uint8_t(uhd::clip(int(stop_reg), 0x0, 0xB)); + +        for(boost::uint8_t start_addr=start_reg; start_addr <= stop_reg; start_addr += sizeof(boost::uint32_t) - 1){ +            int num_bytes = int(stop_reg - start_addr + 1) > int(sizeof(boost::uint32_t)) - 1 ? sizeof(boost::uint32_t) - 1 : stop_reg - start_addr + 1; + +            //create buffer for register data (+1 for start address) +            byte_vector_t regs_vector(num_bytes + 1); + +            //first byte is the address of first register +            regs_vector[0] = start_addr; + +            //get the register data +            for(int i=0; i<num_bytes; i++){ +                regs_vector[1+i] = _max2112_write_regs.get_reg(start_addr+i); +                UHD_LOGV(often) << boost::format( +                    "DBSRX2: send reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" +                ) % int(start_addr+i) % int(regs_vector[1+i]) % int(start_addr) % num_bytes << std::endl; +            } + +            //send the data +            this->get_iface()->write_i2c( +                _max2112_addr(), regs_vector +            ); +        } +    } + +    void read_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg){ +        static const boost::uint8_t status_addr = 0xC; +        start_reg = boost::uint8_t(uhd::clip(int(start_reg), 0x0, 0xD)); +        stop_reg = boost::uint8_t(uhd::clip(int(stop_reg), 0x0, 0xD)); + +        for(boost::uint8_t start_addr=start_reg; start_addr <= stop_reg; start_addr += sizeof(boost::uint32_t)){ +            int num_bytes = int(stop_reg - start_addr + 1) > int(sizeof(boost::uint32_t)) ? sizeof(boost::uint32_t) : stop_reg - start_addr + 1; + +            //create address to start reading register data +            byte_vector_t address_vector(1); +            address_vector[0] = start_addr; + +            //send the address +            this->get_iface()->write_i2c( +                _max2112_addr(), address_vector +            ); + +            //create buffer for register data +            byte_vector_t regs_vector(num_bytes); + +            //read from i2c +            regs_vector = this->get_iface()->read_i2c( +                _max2112_addr(), num_bytes +            ); + +            for(boost::uint8_t i=0; i < num_bytes; i++){ +                if (i + start_addr >= status_addr){ +                    _max2112_read_regs.set_reg(i + start_addr, regs_vector[i]); +                    /* +                    UHD_LOGV(always) << boost::format( +                        "DBSRX2: set reg 0x%02x, value 0x%04x" +                    ) % int(i + start_addr) % int(_max2112_read_regs.get_reg(i + start_addr)) << std::endl; +                    */ +                } +                UHD_LOGV(often) << boost::format( +                    "DBSRX2: read reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" +                ) % int(start_addr+i) % int(regs_vector[i]) % int(start_addr) % num_bytes << std::endl; +            } +        } +    } + +    /*! +     * Get the lock detect status of the LO. +     * \return sensor for locked +     */ +    sensor_value_t get_locked(void){ +        read_reg(0xC, 0xD); + +        //mask and return lock detect +        bool locked = (_max2112_read_regs.ld & _max2112_read_regs.vasa & _max2112_read_regs.vase) != 0; + +        UHD_LOGV(often) << boost::format( +            "DBSRX2 locked: %d" +        ) % locked << std::endl; + +        return sensor_value_t("LO", locked, "locked", "unlocked"); +    } +}; + +/*********************************************************************** + * Register the DBSRX2 dboard + **********************************************************************/ +// FIXME 0x67 is the default i2c address on USRP2 +//       need to handle which side for USRP1 with different address +static dboard_base::sptr make_dbsrx2(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new dbsrx2(args)); +} + +UHD_STATIC_BLOCK(reg_dbsrx2_dboard){ +    //register the factory function for the rx dbid +    dboard_manager::register_dboard(0x0012, &make_dbsrx2, "DBSRX2"); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +dbsrx2::dbsrx2(ctor_args_t args) : rx_dboard_base(args){ +    //send initial register settings +    send_reg(0x0, 0xB); +    //for (boost::uint8_t addr=0; addr<=12; addr++) this->send_reg(addr, addr); + +    //////////////////////////////////////////////////////////////////// +    // Register properties +    //////////////////////////////////////////////////////////////////// +    this->get_rx_subtree()->create<std::string>("name") +        .set("DBSRX2"); +    this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&dbsrx2::get_locked, this)); +    BOOST_FOREACH(const std::string &name, dbsrx2_gain_ranges.keys()){ +        this->get_rx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&dbsrx2::set_gain, this, _1, name)) +            .set(dbsrx2_gain_ranges[name].start()); +        this->get_rx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(dbsrx2_gain_ranges[name]); +    } +    this->get_rx_subtree()->create<double>("freq/value") +        .coerce(boost::bind(&dbsrx2::set_lo_freq, this, _1)) +        .set(dbsrx2_freq_range.start()); +    this->get_rx_subtree()->create<meta_range_t>("freq/range") +        .set(dbsrx2_freq_range); +    this->get_rx_subtree()->create<std::string>("antenna/value") +        .set(dbsrx2_antennas.at(0)); +    this->get_rx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(dbsrx2_antennas); +    this->get_rx_subtree()->create<std::string>("connection") +        .set("QI"); +    this->get_rx_subtree()->create<bool>("enabled") +        .set(true); //always enabled +    this->get_rx_subtree()->create<bool>("use_lo_offset") +        .set(false); + +    double codec_rate = this->get_iface()->get_codec_rate(dboard_iface::UNIT_RX); + +    this->get_rx_subtree()->create<double>("bandwidth/value") +        .coerce(boost::bind(&dbsrx2::set_bandwidth, this, _1)) +        .set(2.0*(0.8*codec_rate/2.0)); //bandwidth in lowpass, convert to complex bandpass +                                        //default to anti-alias at different codec_rate +    this->get_rx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(dbsrx2_bandwidth_range); + +    //enable only the clocks we need +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_RX, true); + +    //set the gpio directions and atr controls (identically) +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, 0x0); // All unused in atr +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, 0x0); // All Inputs + +    get_locked(); +} + +dbsrx2::~dbsrx2(void){ +} + + +/*********************************************************************** + * Tuning + **********************************************************************/ +double dbsrx2::set_lo_freq(double target_freq){ +    //target_freq = dbsrx2_freq_range.clip(target_freq); + +    //variables used in the calculation below +    int scaler = target_freq > 1125e6 ? 2 : 4; +    double ref_freq = this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX); +    int R, intdiv, fracdiv, ext_div; +    double N; + +    //compute tuning variables +    ext_div = dbsrx2_ref_divider; // 12MHz < ref_freq/ext_divider < 30MHz + +    R = 1; //Divide by 1 is the only tested value + +    N = (target_freq*R*ext_div)/(ref_freq); //actual spec range is (19, 251) +    intdiv = int(std::floor(N)); //  if (intdiv < 19  or intdiv > 251) continue; +    fracdiv = boost::math::iround((N - intdiv)*double(1 << 20)); + +    //calculate the actual freq from the values above +    N = double(intdiv) + double(fracdiv)/double(1 << 20); +    _lo_freq = (N*ref_freq)/(R*ext_div); + +    //load new counters into registers +    _max2112_write_regs.set_n_divider(intdiv); +    _max2112_write_regs.set_f_divider(fracdiv); +    _max2112_write_regs.r_divider = R; +    _max2112_write_regs.d24 = scaler == 4 ? max2112_write_regs_t::D24_DIV4 : max2112_write_regs_t::D24_DIV2; + +    //debug output of calculated variables +    UHD_LOGV(often) +        << boost::format("DBSRX2 tune:\n") +        << boost::format("    R=%d, N=%f, scaler=%d, ext_div=%d\n") % R % N % scaler % ext_div +        << boost::format("    int=%d, frac=%d, d24=%d\n") % intdiv % fracdiv % int(_max2112_write_regs.d24) +        << boost::format("    Ref    Freq=%fMHz\n") % (ref_freq/1e6) +        << boost::format("    Target Freq=%fMHz\n") % (target_freq/1e6) +        << boost::format("    Actual Freq=%fMHz\n") % (_lo_freq/1e6) +        << std::endl; + +    //send the registers +    send_reg(0x0, 0x7); + +    //FIXME: probably unnecessary to call get_locked here +    //get_locked(); + +    return _lo_freq; +} + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +/*! + * Convert a requested gain for the BBG vga into the integer register value. + * The gain passed into the function will be set to the actual value. + * \param gain the requested gain in dB + * \return 4 bit the register value + */ +static int gain_to_bbg_vga_reg(double &gain){ +    int reg = boost::math::iround(dbsrx2_gain_ranges["BBG"].clip(gain)); + +    gain = double(reg); + +    UHD_LOGV(often) +        << boost::format("DBSRX2 BBG Gain:\n") +        << boost::format("    %f dB, bbg: %d") % gain % reg  +        << std::endl; + +    return reg; +} + +/*! + * Convert a requested gain for the GC1 rf vga into the dac_volts value. + * The gain passed into the function will be set to the actual value. + * \param gain the requested gain in dB + * \return dac voltage value + */ +static double gain_to_gc1_rfvga_dac(double &gain){ +    //clip the input +    gain = dbsrx2_gain_ranges["GC1"].clip(gain); + +    //voltage level constants +    static const double max_volts = 0.5, min_volts = 2.7; +    static const double slope = (max_volts-min_volts)/dbsrx2_gain_ranges["GC1"].stop(); + +    //calculate the voltage for the aux dac +    double dac_volts = gain*slope + min_volts; + +    UHD_LOGV(often) +        << boost::format("DBSRX2 GC1 Gain:\n") +        << boost::format("    %f dB, dac_volts: %f V") % gain % dac_volts  +        << std::endl; + +    //the actual gain setting +    gain = (dac_volts - min_volts)/slope; + +    return dac_volts; +} + +double dbsrx2::set_gain(double gain, const std::string &name){ +    assert_has(dbsrx2_gain_ranges.keys(), name, "dbsrx2 gain name"); +    if (name == "BBG"){ +        _max2112_write_regs.bbg = gain_to_bbg_vga_reg(gain); +        send_reg(0x9, 0x9); +    } +    else if(name == "GC1"){ +        //write the new voltage to the aux dac +        this->get_iface()->write_aux_dac(dboard_iface::UNIT_RX, dboard_iface::AUX_DAC_A, gain_to_gc1_rfvga_dac(gain)); +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    _gains[name] = gain; + +    return gain; +} + +/*********************************************************************** + * Bandwidth Handling + **********************************************************************/ +double dbsrx2::set_bandwidth(double bandwidth){ +    //convert complex bandpass to lowpass bandwidth +    bandwidth = bandwidth/2.0; + +    //clip the input +    bandwidth = dbsrx2_bandwidth_range.clip(bandwidth); + +    _max2112_write_regs.lp = int((bandwidth/1e6 - 4)/0.29 + 12); +    _bandwidth = double(4 + (_max2112_write_regs.lp - 12) * 0.29)*1e6; + +    UHD_LOGV(often) +        << boost::format("DBSRX2 Bandwidth:\n") +        << boost::format("    %f MHz, lp: %f V") % (_bandwidth/1e6) % int(_max2112_write_regs.lp) +        << std::endl; + +    this->send_reg(0x8, 0x8); + +    //convert lowpass back to complex bandpass bandwidth +    return 2.0*_bandwidth; +} diff --git a/host/lib/usrp/dboard/db_rfx.cpp b/host/lib/usrp/dboard/db_rfx.cpp new file mode 100644 index 000000000..cf3b29ddc --- /dev/null +++ b/host/lib/usrp/dboard/db_rfx.cpp @@ -0,0 +1,449 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +// IO Pin functions +#define POWER_IO     (1 << 7)   // Low enables power supply +#define ANTSW_IO     (1 << 6)   // On TX DB, 0 = TX, 1 = RX, on RX DB 0 = main ant, 1 = RX2 +#define MIXER_IO     (1 << 5)   // Enable appropriate mixer +#define LOCKDET_MASK (1 << 2)   // Input pin + +// Mixer constants +#define MIXER_ENB    MIXER_IO +#define MIXER_DIS    0 + +// Antenna constants +#define ANT_TX       0          //the tx line is transmitting +#define ANT_RX       ANTSW_IO   //the tx line is receiving +#define ANT_TXRX     0          //the rx line is on txrx +#define ANT_RX2      ANTSW_IO   //the rx line in on rx2 +#define ANT_XX       0          //dont care how the antenna is set + +#include "adf4360_regs.hpp" +#include <uhd/types/dict.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/log.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/usrp/dboard_id.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/bind.hpp> +#include <boost/format.hpp> +#include <boost/math/special_functions/round.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +/*********************************************************************** + * The RFX Series constants + **********************************************************************/ +static const std::vector<std::string> rfx_tx_antennas = list_of("TX/RX")("CAL"); + +static const std::vector<std::string> rfx_rx_antennas = list_of("TX/RX")("RX2")("CAL"); + +static const uhd::dict<std::string, gain_range_t> rfx_rx_gain_ranges = map_list_of +    ("PGA0", gain_range_t(0, 70, 0.022)) +; + +static const uhd::dict<std::string, gain_range_t> rfx400_rx_gain_ranges = map_list_of +    ("PGA0", gain_range_t(0, 45, 0.022)) +; + +/*********************************************************************** + * The RFX series of dboards + **********************************************************************/ +class rfx_xcvr : public xcvr_dboard_base{ +public: +    rfx_xcvr( +        ctor_args_t args, +        const freq_range_t &freq_range, +        bool rx_div2, bool tx_div2 +    ); +    ~rfx_xcvr(void); + +private: +    const freq_range_t _freq_range; +    const uhd::dict<std::string, gain_range_t> _rx_gain_ranges; +    const uhd::dict<dboard_iface::unit_t, bool> _div2; +    std::string  _rx_ant; +    uhd::dict<std::string, double> _rx_gains; +    boost::uint16_t _power_up; + +    void set_rx_ant(const std::string &ant); +    void set_tx_ant(const std::string &ant); +    double set_rx_gain(double gain, const std::string &name); + +    /*! +     * Set the LO frequency for the particular dboard unit. +     * \param unit which unit rx or tx +     * \param target_freq the desired frequency in Hz +     * \return the actual frequency in Hz +     */ +    double set_lo_freq(dboard_iface::unit_t unit, double target_freq); + +    /*! +     * Get the lock detect status of the LO. +     * \param unit which unit rx or tx +     * \return sensor for locked +     */ +    sensor_value_t get_locked(dboard_iface::unit_t unit){ +        const bool locked = (this->get_iface()->read_gpio(unit) & LOCKDET_MASK) != 0; +        return sensor_value_t("LO", locked, "locked", "unlocked"); +    } + +    /*! +     * Removed incorrect/confusing RSSI calculation +     * Limited dynamic range of sensor makes this less useful +     */ +}; + +/*********************************************************************** + * Register the RFX dboards (min freq, max freq, rx div2, tx div2) + **********************************************************************/ +static dboard_base::sptr make_rfx_flex400(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new rfx_xcvr(args, freq_range_t(400e6, 500e6), true, true)); +} + +static dboard_base::sptr make_rfx_flex900(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new rfx_xcvr(args, freq_range_t(750e6, 1050e6), true, true)); +} + +static dboard_base::sptr make_rfx_flex1800(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new rfx_xcvr(args, freq_range_t(1500e6, 2100e6), false, false)); +} + +static dboard_base::sptr make_rfx_flex1200(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new rfx_xcvr(args, freq_range_t(1150e6, 1450e6), true, true)); +} + +static dboard_base::sptr make_rfx_flex2200(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new rfx_xcvr(args, freq_range_t(2000e6, 2400e6), false, false)); +} + +static dboard_base::sptr make_rfx_flex2400(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new rfx_xcvr(args, freq_range_t(2300e6, 2900e6), false, false)); +} + +UHD_STATIC_BLOCK(reg_rfx_dboards){ +    dboard_manager::register_dboard(0x0024, 0x0028, &make_rfx_flex400,  "RFX400"); +    dboard_manager::register_dboard(0x0025, 0x0029, &make_rfx_flex900,  "RFX900"); +    dboard_manager::register_dboard(0x0034, 0x0035, &make_rfx_flex1800, "RFX1800"); +    dboard_manager::register_dboard(0x0026, 0x002a, &make_rfx_flex1200, "RFX1200"); +    dboard_manager::register_dboard(0x002c, 0x002d, &make_rfx_flex2200, "RFX2200"); +    dboard_manager::register_dboard(0x0027, 0x002b, &make_rfx_flex2400, "RFX2400"); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +rfx_xcvr::rfx_xcvr( +    ctor_args_t args, +    const freq_range_t &freq_range, +    bool rx_div2, bool tx_div2 +): +    xcvr_dboard_base(args), +    _freq_range(freq_range), +    _rx_gain_ranges((get_rx_id() == 0x0024)? +        rfx400_rx_gain_ranges : rfx_rx_gain_ranges +    ), +    _div2(map_list_of +        (dboard_iface::UNIT_RX, rx_div2) +        (dboard_iface::UNIT_TX, tx_div2) +    ), +    _power_up((get_rx_id() == 0x0024 && get_tx_id() == 0x0028) ? POWER_IO : 0) +{ +    //////////////////////////////////////////////////////////////////// +    // Register RX properties +    //////////////////////////////////////////////////////////////////// +    if(get_rx_id() == 0x0024) this->get_rx_subtree()->create<std::string>("name").set("RFX400 RX"); +    else if(get_rx_id() == 0x0025) this->get_rx_subtree()->create<std::string>("name").set("RFX900 RX"); +    else if(get_rx_id() == 0x0034) this->get_rx_subtree()->create<std::string>("name").set("RFX1800 RX"); +    else if(get_rx_id() == 0x0026) this->get_rx_subtree()->create<std::string>("name").set("RFX1200 RX"); +    else if(get_rx_id() == 0x002c) this->get_rx_subtree()->create<std::string>("name").set("RFX2200 RX"); +    else if(get_rx_id() == 0x0027) this->get_rx_subtree()->create<std::string>("name").set("RFX2400 RX"); +    else this->get_rx_subtree()->create<std::string>("name").set("RFX RX"); + +    this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&rfx_xcvr::get_locked, this, dboard_iface::UNIT_RX)); +    BOOST_FOREACH(const std::string &name, _rx_gain_ranges.keys()){ +        this->get_rx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&rfx_xcvr::set_rx_gain, this, _1, name)) +            .set(_rx_gain_ranges[name].start()); +        this->get_rx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(_rx_gain_ranges[name]); +    } +    this->get_rx_subtree()->create<double>("freq/value") +        .coerce(boost::bind(&rfx_xcvr::set_lo_freq, this, dboard_iface::UNIT_RX, _1)) +        .set((_freq_range.start() + _freq_range.stop())/2.0); +    this->get_rx_subtree()->create<meta_range_t>("freq/range").set(_freq_range); +    this->get_rx_subtree()->create<std::string>("antenna/value") +        .subscribe(boost::bind(&rfx_xcvr::set_rx_ant, this, _1)) +        .set("RX2"); +    this->get_rx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(rfx_rx_antennas); +    this->get_rx_subtree()->create<std::string>("connection").set("QI"); +    this->get_rx_subtree()->create<bool>("enabled").set(true); //always enabled +    this->get_rx_subtree()->create<bool>("use_lo_offset").set(false); +    this->get_rx_subtree()->create<double>("bandwidth/value").set(2*20.0e6); //20MHz low-pass, we want complex double-sided +    this->get_rx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(2*20.0e6, 2*20.0e6)); + +    //////////////////////////////////////////////////////////////////// +    // Register TX properties +    //////////////////////////////////////////////////////////////////// +    if(get_tx_id() == 0x0028) this->get_tx_subtree()->create<std::string>("name").set("RFX400 TX"); +    else if(get_tx_id() == 0x0029) this->get_tx_subtree()->create<std::string>("name").set("RFX900 TX"); +    else if(get_tx_id() == 0x0035) this->get_tx_subtree()->create<std::string>("name").set("RFX1800 TX"); +    else if(get_tx_id() == 0x002a) this->get_tx_subtree()->create<std::string>("name").set("RFX1200 TX"); +    else if(get_tx_id() == 0x002d) this->get_tx_subtree()->create<std::string>("name").set("RFX2200 TX"); +    else if(get_tx_id() == 0x002b) this->get_tx_subtree()->create<std::string>("name").set("RFX2400 TX"); +    else this->get_tx_subtree()->create<std::string>("name").set("RFX TX"); + +    this->get_tx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&rfx_xcvr::get_locked, this, dboard_iface::UNIT_TX)); +    this->get_tx_subtree()->create<int>("gains"); //phony property so this dir exists +    this->get_tx_subtree()->create<double>("freq/value") +        .coerce(boost::bind(&rfx_xcvr::set_lo_freq, this, dboard_iface::UNIT_TX, _1)) +        .set((_freq_range.start() + _freq_range.stop())/2.0); +    this->get_tx_subtree()->create<meta_range_t>("freq/range").set(_freq_range); +    this->get_tx_subtree()->create<std::string>("antenna/value") +        .subscribe(boost::bind(&rfx_xcvr::set_tx_ant, this, _1)).set(rfx_tx_antennas.at(0)); +    this->get_tx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(rfx_tx_antennas); +    this->get_tx_subtree()->create<std::string>("connection").set("IQ"); +    this->get_tx_subtree()->create<bool>("enabled").set(true); //always enabled +    this->get_tx_subtree()->create<bool>("use_lo_offset").set(true); +    this->get_tx_subtree()->create<double>("bandwidth/value").set(2*20.0e6); //20MHz low-pass, we want complex double-sided +    this->get_tx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(2*20.0e6, 2*20.0e6)); + +    //enable the clocks that we need +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_TX, true); +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_RX, true); + +    //set the gpio directions and atr controls (identically) +    boost::uint16_t output_enables = POWER_IO | ANTSW_IO | MIXER_IO; +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_TX, output_enables); +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, output_enables); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_TX, output_enables); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, output_enables); + +    //setup the tx atr (this does not change with antenna) +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_IDLE,        _power_up | ANT_XX | MIXER_DIS); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_RX_ONLY,     _power_up | ANT_RX | MIXER_DIS); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     _power_up | ANT_TX | MIXER_ENB); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, _power_up | ANT_TX | MIXER_ENB); + +    //setup the rx atr (this does not change with antenna) +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_IDLE,        _power_up | ANT_XX | MIXER_DIS); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_TX_ONLY,     _power_up | ANT_XX | MIXER_DIS); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_FULL_DUPLEX, _power_up | ANT_RX2| MIXER_ENB); +} + +rfx_xcvr::~rfx_xcvr(void){ +    /* NOP */ +} + +/*********************************************************************** + * Antenna Handling + **********************************************************************/ +void rfx_xcvr::set_rx_ant(const std::string &ant){ +    //validate input +    assert_has(rfx_rx_antennas, ant, "rfx rx antenna name"); + +    //set the rx atr regs that change with antenna setting +    if (ant == "CAL") { +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_TX_ONLY,     _power_up | ANT_TXRX  | MIXER_ENB); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_FULL_DUPLEX, _power_up | ANT_TXRX  | MIXER_ENB); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_RX_ONLY,     _power_up | MIXER_ENB | ANT_TXRX ); +    }  +    else { +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_TX_ONLY,     _power_up | ANT_XX | MIXER_DIS); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_FULL_DUPLEX, _power_up | ANT_RX2| MIXER_ENB); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_RX_ONLY,     _power_up | MIXER_ENB | +            ((ant == "TX/RX")? ANT_TXRX : ANT_RX2)); +    } + +    //shadow the setting +    _rx_ant = ant; +} + +void rfx_xcvr::set_tx_ant(const std::string &ant){ +    assert_has(rfx_tx_antennas, ant, "rfx tx antenna name"); + +    //set the tx atr regs that change with antenna setting +    if (ant == "CAL") { +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     _power_up | ANT_RX | MIXER_ENB); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, _power_up | ANT_RX | MIXER_ENB); +    }  +    else { +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     _power_up | ANT_TX | MIXER_ENB); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, _power_up | ANT_TX | MIXER_ENB); +    } +} + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +static double rx_pga0_gain_to_dac_volts(double &gain, double range){ +    //voltage level constants (negative slope) +    static const double max_volts = .2, min_volts = 1.2; +    static const double slope = (max_volts-min_volts)/(range); + +    //calculate the voltage for the aux dac +    double dac_volts = uhd::clip<double>(gain*slope + min_volts, max_volts, min_volts); + +    //the actual gain setting +    gain = (dac_volts - min_volts)/slope; + +    return dac_volts; +} + +double rfx_xcvr::set_rx_gain(double gain, const std::string &name){ +    assert_has(_rx_gain_ranges.keys(), name, "rfx rx gain name"); +    if(name == "PGA0"){ +        double dac_volts = rx_pga0_gain_to_dac_volts(gain,  +                              (_rx_gain_ranges["PGA0"].stop() - _rx_gain_ranges["PGA0"].start())); + +        //write the new voltage to the aux dac +        this->get_iface()->write_aux_dac(dboard_iface::UNIT_RX, dboard_iface::AUX_DAC_A, dac_volts); + +        return gain; +    } +    else UHD_THROW_INVALID_CODE_PATH(); +} + +/*********************************************************************** + * Tuning + **********************************************************************/ +double rfx_xcvr::set_lo_freq( +    dboard_iface::unit_t unit, +    double target_freq +){ +    UHD_LOGV(often) << boost::format( +        "RFX tune: target frequency %f Mhz" +    ) % (target_freq/1e6) << std::endl; + +    //clip the input +    target_freq = _freq_range.clip(target_freq); +    if (_div2[unit]) target_freq *= 2; + +    //rfx400 rx is a special case with div2 in mixer, so adf4360 must output fundamental +    bool is_rx_rfx400 = ((get_rx_id() == 0x0024) && unit != dboard_iface::UNIT_TX); + +    //map prescalers to the register enums +    static const uhd::dict<int, adf4360_regs_t::prescaler_value_t> prescaler_to_enum = map_list_of +        (8,  adf4360_regs_t::PRESCALER_VALUE_8_9) +        (16, adf4360_regs_t::PRESCALER_VALUE_16_17) +        (32, adf4360_regs_t::PRESCALER_VALUE_32_33) +    ; + +    //map band select clock dividers to enums +    static const uhd::dict<int, adf4360_regs_t::band_select_clock_div_t> bandsel_to_enum = map_list_of +        (1, adf4360_regs_t::BAND_SELECT_CLOCK_DIV_1) +        (2, adf4360_regs_t::BAND_SELECT_CLOCK_DIV_2) +        (4, adf4360_regs_t::BAND_SELECT_CLOCK_DIV_4) +        (8, adf4360_regs_t::BAND_SELECT_CLOCK_DIV_8) +    ; + +    double actual_freq=0, ref_freq = this->get_iface()->get_clock_rate(unit); +    int R=0, BS=0, P=0, B=0, A=0; + +    /* +     * The goal here to to loop though possible R dividers, +     * band select clock dividers, and prescaler values. +     * Calculate the A and B counters for each set of values. +     * The loop exits when it meets all of the constraints. +     * The resulting loop values are loaded into the registers. +     * +     * fvco = [P*B + A] * fref/R +     * fvco*R/fref = P*B + A = N +     */ +    for(R = 2; R <= 32; R+=2){ +        BOOST_FOREACH(BS, bandsel_to_enum.keys()){ +            if (ref_freq/R/BS > 1e6) continue; //constraint on band select clock +            BOOST_FOREACH(P, prescaler_to_enum.keys()){ +                //calculate B and A from N +                double N = target_freq*R/ref_freq; +                B = int(std::floor(N/P)); +                A = boost::math::iround(N - P*B); +                if (B < A or B > 8191 or B < 3 or A > 31) continue; //constraints on A, B +                //calculate the actual frequency +                actual_freq = double(P*B + A)*ref_freq/R; +                if (actual_freq/P > 300e6) continue; //constraint on prescaler output +                //constraints met: exit loop +                goto done_loop; +            } +        } +    } done_loop: + +    UHD_LOGV(often) << boost::format( +        "RFX tune: R=%d, BS=%d, P=%d, B=%d, A=%d, DIV2=%d" +    ) % R % BS % P % B % A % int(_div2[unit] && (!is_rx_rfx400)) << std::endl; + +    //load the register values +    adf4360_regs_t regs; +    regs.core_power_level        = adf4360_regs_t::CORE_POWER_LEVEL_10MA; +    regs.counter_operation       = adf4360_regs_t::COUNTER_OPERATION_NORMAL; +    regs.muxout_control          = adf4360_regs_t::MUXOUT_CONTROL_DLD; +    regs.phase_detector_polarity = adf4360_regs_t::PHASE_DETECTOR_POLARITY_POS; +    regs.charge_pump_output      = adf4360_regs_t::CHARGE_PUMP_OUTPUT_NORMAL; +    regs.cp_gain_0               = adf4360_regs_t::CP_GAIN_0_SET1; +    regs.mute_till_ld            = adf4360_regs_t::MUTE_TILL_LD_ENB; +    regs.output_power_level      = adf4360_regs_t::OUTPUT_POWER_LEVEL_3_5MA; +    regs.current_setting1        = adf4360_regs_t::CURRENT_SETTING1_0_31MA; +    regs.current_setting2        = adf4360_regs_t::CURRENT_SETTING2_0_31MA; +    regs.power_down              = adf4360_regs_t::POWER_DOWN_NORMAL_OP; +    regs.prescaler_value         = prescaler_to_enum[P]; +    regs.a_counter               = A; +    regs.b_counter               = B; +    regs.cp_gain_1               = adf4360_regs_t::CP_GAIN_1_SET1; +    regs.divide_by_2_output      = (_div2[unit] && (!is_rx_rfx400)) ?  // Special case RFX400 RX Mixer divides by two +                                    adf4360_regs_t::DIVIDE_BY_2_OUTPUT_DIV2 : +                                    adf4360_regs_t::DIVIDE_BY_2_OUTPUT_FUND ; +    regs.divide_by_2_prescaler   = adf4360_regs_t::DIVIDE_BY_2_PRESCALER_FUND; +    regs.r_counter               = R; +    regs.ablpw                   = adf4360_regs_t::ABLPW_3_0NS; +    regs.lock_detect_precision   = adf4360_regs_t::LOCK_DETECT_PRECISION_5CYCLES; +    regs.test_mode_bit           = 0; +    regs.band_select_clock_div   = bandsel_to_enum[BS]; + +    //write the registers +    std::vector<adf4360_regs_t::addr_t> addrs = list_of //correct power-up sequence to write registers (R, C, N) +        (adf4360_regs_t::ADDR_RCOUNTER) +        (adf4360_regs_t::ADDR_CONTROL) +        (adf4360_regs_t::ADDR_NCOUNTER) +    ; +    BOOST_FOREACH(adf4360_regs_t::addr_t addr, addrs){ +        this->get_iface()->write_spi( +            unit, spi_config_t::EDGE_RISE, +            regs.get_reg(addr), 24 +        ); +    } + +    //return the actual frequency +    if (_div2[unit]) actual_freq /= 2; +    UHD_LOGV(often) << boost::format( +        "RFX tune: actual frequency %f Mhz" +    ) % (actual_freq/1e6) << std::endl; +    return actual_freq; +} diff --git a/host/lib/usrp/dboard/db_sbx_common.cpp b/host/lib/usrp/dboard/db_sbx_common.cpp new file mode 100644 index 000000000..a51dee361 --- /dev/null +++ b/host/lib/usrp/dboard/db_sbx_common.cpp @@ -0,0 +1,357 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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 "db_sbx_common.hpp" +#include "adf4350_regs.hpp" + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + + +/*********************************************************************** + * Register the SBX dboard (min freq, max freq, rx div2, tx div2) + **********************************************************************/ +static dboard_base::sptr make_sbx(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new sbx_xcvr(args)); +} + +UHD_STATIC_BLOCK(reg_sbx_dboards){ +    dboard_manager::register_dboard(0x0054, 0x0055, &make_sbx, "SBX"); +    dboard_manager::register_dboard(0x0065, 0x0064, &make_sbx, "SBX v4"); +} + + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +static int rx_pga0_gain_to_iobits(double &gain){ +    //clip the input +    gain = sbx_rx_gain_ranges["PGA0"].clip(gain); + +    //convert to attenuation and update iobits for atr +    double attn = sbx_rx_gain_ranges["PGA0"].stop() - gain; + +    //calculate the RX attenuation +    int attn_code = int(floor(attn*2)); +    int iobits = ((~attn_code) << RX_ATTN_SHIFT) & RX_ATTN_MASK; + +    UHD_LOGV(often) << boost::format( +        "SBX TX Attenuation: %f dB, Code: %d, IO Bits %x, Mask: %x" +    ) % attn % attn_code % (iobits & RX_ATTN_MASK) % RX_ATTN_MASK << std::endl; + +    //the actual gain setting +    gain = sbx_rx_gain_ranges["PGA0"].stop() - double(attn_code)/2; + +    return iobits; +} + +static int tx_pga0_gain_to_iobits(double &gain){ +    //clip the input +    gain = sbx_tx_gain_ranges["PGA0"].clip(gain); + +    //convert to attenuation and update iobits for atr +    double attn = sbx_tx_gain_ranges["PGA0"].stop() - gain; + +    //calculate the TX attenuation +    int attn_code = int(floor(attn*2)); +    int iobits = ((~attn_code) << TX_ATTN_SHIFT) & TX_ATTN_MASK; + +    UHD_LOGV(often) << boost::format( +        "SBX TX Attenuation: %f dB, Code: %d, IO Bits %x, Mask: %x" +    ) % attn % attn_code % (iobits & TX_ATTN_MASK) % TX_ATTN_MASK << std::endl; + +    //the actual gain setting +    gain = sbx_tx_gain_ranges["PGA0"].stop() - double(attn_code)/2; + +    return iobits; +} + +double sbx_xcvr::set_tx_gain(double gain, const std::string &name){ +    assert_has(sbx_tx_gain_ranges.keys(), name, "sbx tx gain name"); +    if(name == "PGA0"){ +        tx_pga0_gain_to_iobits(gain); +        _tx_gains[name] = gain; + +        //write the new gain to atr regs +        update_atr(); +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    return _tx_gains[name]; +} + +double sbx_xcvr::set_rx_gain(double gain, const std::string &name){ +    assert_has(sbx_rx_gain_ranges.keys(), name, "sbx rx gain name"); +    if(name == "PGA0"){ +        rx_pga0_gain_to_iobits(gain); +        _rx_gains[name] = gain; + +        //write the new gain to atr regs +        update_atr(); +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    return _rx_gains[name]; +} + + +/*********************************************************************** + * Structors + **********************************************************************/ +sbx_xcvr::sbx_xcvr(ctor_args_t args) : xcvr_dboard_base(args){ +    switch(get_rx_id().to_uint16()) { +        case 0x054: +            db_actual = sbx_versionx_sptr(new sbx_version3(this)); +            break; +        case 0x065: +            db_actual = sbx_versionx_sptr(new sbx_version4(this)); +            break; +        default: +            /* We didn't recognize the version of the board... */ +            UHD_THROW_INVALID_CODE_PATH(); +    } + +    //////////////////////////////////////////////////////////////////// +    // Register RX properties +    //////////////////////////////////////////////////////////////////// +    if(get_rx_id() == 0x054) this->get_rx_subtree()->create<std::string>("name").set("SBXv3 RX"); +    else if(get_rx_id() == 0x065) this->get_rx_subtree()->create<std::string>("name").set("SBXv4 RX"); +    else this->get_rx_subtree()->create<std::string>("name").set("SBX RX"); + +    this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&sbx_xcvr::get_locked, this, dboard_iface::UNIT_RX)); +    BOOST_FOREACH(const std::string &name, sbx_rx_gain_ranges.keys()){ +        this->get_rx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&sbx_xcvr::set_rx_gain, this, _1, name)) +            .set(sbx_rx_gain_ranges[name].start()); +        this->get_rx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(sbx_rx_gain_ranges[name]); +    } +    this->get_rx_subtree()->create<double>("freq/value") +        .coerce(boost::bind(&sbx_xcvr::set_lo_freq, this, dboard_iface::UNIT_RX, _1)) +        .set((sbx_freq_range.start() + sbx_freq_range.stop())/2.0); +    this->get_rx_subtree()->create<meta_range_t>("freq/range").set(sbx_freq_range); +    this->get_rx_subtree()->create<std::string>("antenna/value") +        .subscribe(boost::bind(&sbx_xcvr::set_rx_ant, this, _1)) +        .set("RX2"); +    this->get_rx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(sbx_rx_antennas); +    this->get_rx_subtree()->create<std::string>("connection").set("IQ"); +    this->get_rx_subtree()->create<bool>("enabled").set(true); //always enabled +    this->get_rx_subtree()->create<bool>("use_lo_offset").set(false); +    this->get_rx_subtree()->create<double>("bandwidth/value").set(2*20.0e6); //20MHz low-pass, we want complex double-sided +    this->get_rx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(2*20.0e6, 2*20.0e6)); + +    //////////////////////////////////////////////////////////////////// +    // Register TX properties +    //////////////////////////////////////////////////////////////////// +    if(get_tx_id() == 0x055) this->get_tx_subtree()->create<std::string>("name").set("SBXv3 TX"); +    else if(get_tx_id() == 0x067) this->get_tx_subtree()->create<std::string>("name").set("SBXv4 TX"); +    else this->get_tx_subtree()->create<std::string>("name").set("SBX TX"); + +    this->get_tx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&sbx_xcvr::get_locked, this, dboard_iface::UNIT_TX)); +    BOOST_FOREACH(const std::string &name, sbx_tx_gain_ranges.keys()){ +        this->get_tx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&sbx_xcvr::set_tx_gain, this, _1, name)) +            .set(sbx_tx_gain_ranges[name].start()); +        this->get_tx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(sbx_tx_gain_ranges[name]); +    } +    this->get_tx_subtree()->create<double>("freq/value") +        .coerce(boost::bind(&sbx_xcvr::set_lo_freq, this, dboard_iface::UNIT_TX, _1)) +        .set((sbx_freq_range.start() + sbx_freq_range.stop())/2.0); +    this->get_tx_subtree()->create<meta_range_t>("freq/range").set(sbx_freq_range); +    this->get_tx_subtree()->create<std::string>("antenna/value") +        .subscribe(boost::bind(&sbx_xcvr::set_tx_ant, this, _1)) +        .set(sbx_tx_antennas.at(0)); +    this->get_tx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(sbx_tx_antennas); +    this->get_tx_subtree()->create<std::string>("connection").set("QI"); +    this->get_tx_subtree()->create<bool>("enabled").set(true); //always enabled +    this->get_tx_subtree()->create<bool>("use_lo_offset").set(false); +    this->get_tx_subtree()->create<double>("bandwidth/value").set(2*20.0e6); //20MHz low-pass, we want complex double-sided +    this->get_tx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(2*20.0e6, 2*20.0e6)); + +    //enable the clocks that we need +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_TX, true); +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_RX, true); + +    //set the gpio directions and atr controls (identically) +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_TX, (TXIO_MASK|TX_LED_IO)); +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, (RXIO_MASK|RX_LED_IO)); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_TX, (TXIO_MASK|TX_LED_IO)); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, (RXIO_MASK|RX_LED_IO)); + +    //flash LEDs +    flash_leds(); + +    UHD_LOGV(often) << boost::format( +        "SBX GPIO Direction: RX: 0x%08x, TX: 0x%08x" +    ) % RXIO_MASK % TXIO_MASK << std::endl; +} + +sbx_xcvr::~sbx_xcvr(void){ +    /* NOP */ +} + +/*********************************************************************** + * Antenna Handling + **********************************************************************/ +void sbx_xcvr::update_atr(void){ +    //calculate atr pins +    int rx_pga0_iobits = rx_pga0_gain_to_iobits(_rx_gains["PGA0"]); +    int tx_pga0_iobits = tx_pga0_gain_to_iobits(_tx_gains["PGA0"]); +    int rx_lo_lpf_en = (_rx_lo_freq == sbx_enable_rx_lo_filter.clip(_rx_lo_freq)) ? LO_LPF_EN : 0; +    int tx_lo_lpf_en = (_tx_lo_freq == sbx_enable_tx_lo_filter.clip(_tx_lo_freq)) ? LO_LPF_EN : 0; +    int rx_ld_led = _rx_lo_lock_cache ? 0 : RX_LED_LD; +    int tx_ld_led = _tx_lo_lock_cache ? 0 : TX_LED_LD; +    int rx_ant_led = _rx_ant == "TX/RX" ? RX_LED_RX1RX2 : 0; +    int tx_ant_led = _tx_ant == "TX/RX" ? 0 : TX_LED_TXRX; + +    //setup the tx atr (this does not change with antenna) +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, \ +            dboard_iface::ATR_REG_IDLE, 0 | tx_lo_lpf_en \ +            | tx_ld_led | tx_ant_led | TX_POWER_UP | ANT_XX | TX_MIXER_DIS); + +    //setup the rx atr (this does not change with antenna) +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, \ +            dboard_iface::ATR_REG_IDLE, rx_pga0_iobits | rx_lo_lpf_en \ +            | rx_ld_led | rx_ant_led | RX_POWER_UP | ANT_XX | RX_MIXER_DIS); + +    //set the RX atr regs that change with antenna setting +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, \ +            dboard_iface::ATR_REG_RX_ONLY, rx_pga0_iobits | rx_lo_lpf_en \ +            | rx_ld_led | rx_ant_led | RX_POWER_UP | RX_MIXER_ENB \ +            | ((_rx_ant != "RX2")? ANT_TXRX : ANT_RX2)); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, \ +            dboard_iface::ATR_REG_TX_ONLY, rx_pga0_iobits | rx_lo_lpf_en \ +            | rx_ld_led | rx_ant_led | RX_POWER_UP | RX_MIXER_DIS \ +            | ((_rx_ant == "CAL")? ANT_TXRX : ANT_RX2)); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, \ +            dboard_iface::ATR_REG_FULL_DUPLEX, rx_pga0_iobits | rx_lo_lpf_en \ +            | rx_ld_led | rx_ant_led | RX_POWER_UP | RX_MIXER_ENB \ +            | ((_rx_ant == "CAL")? ANT_TXRX : ANT_RX2)); + +    //set the TX atr regs that change with antenna setting +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, \ +            dboard_iface::ATR_REG_RX_ONLY, 0 | tx_lo_lpf_en \ +            | tx_ld_led | tx_ant_led | TX_POWER_UP | TX_MIXER_DIS \ +            | ((_rx_ant != "RX2")? ANT_RX : ANT_TX)); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, \ +            dboard_iface::ATR_REG_TX_ONLY, tx_pga0_iobits | tx_lo_lpf_en \ +            | tx_ld_led | tx_ant_led | TX_POWER_UP | TX_MIXER_ENB \ +            | ((_tx_ant == "CAL")? ANT_RX : ANT_TX)); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, \ +            dboard_iface::ATR_REG_FULL_DUPLEX, tx_pga0_iobits | tx_lo_lpf_en \ +            | tx_ld_led | tx_ant_led | TX_POWER_UP | TX_MIXER_ENB \ +            | ((_tx_ant == "CAL")? ANT_RX : ANT_TX)); +} + +void sbx_xcvr::set_rx_ant(const std::string &ant){ +    //validate input +    assert_has(sbx_rx_antennas, ant, "sbx rx antenna name"); + +    //shadow the setting +    _rx_ant = ant; + +    //write the new antenna setting to atr regs +    update_atr(); +} + +void sbx_xcvr::set_tx_ant(const std::string &ant){ +    assert_has(sbx_tx_antennas, ant, "sbx tx antenna name"); + +    //shadow the setting +    _tx_ant = ant; + +    //write the new antenna setting to atr regs +    update_atr(); +} + +/*********************************************************************** + * Tuning + **********************************************************************/ +double sbx_xcvr::set_lo_freq(dboard_iface::unit_t unit, double target_freq) { +    const double actual = db_actual->set_lo_freq(unit, target_freq); +    if (unit == dboard_iface::UNIT_RX){ +        _rx_lo_lock_cache = false; +        _rx_lo_freq = actual; +    } +    if (unit == dboard_iface::UNIT_TX){ +        _tx_lo_lock_cache = false; +        _tx_lo_freq = actual; +    } +    update_atr(); +    return actual; +} + + +sensor_value_t sbx_xcvr::get_locked(dboard_iface::unit_t unit) { +    const bool locked = (this->get_iface()->read_gpio(unit) & LOCKDET_MASK) != 0; + +    if (unit == dboard_iface::UNIT_RX) _rx_lo_lock_cache = locked; +    if (unit == dboard_iface::UNIT_TX) _tx_lo_lock_cache = locked; + +    //write the new lock cache setting to atr regs +    update_atr(); + +    return sensor_value_t("LO", locked, "locked", "unlocked"); +} + + +void sbx_xcvr::flash_leds(void) { +    //Remove LED gpios from ATR control temporarily and set to outputs +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_TX, TXIO_MASK); +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, RXIO_MASK); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_TX, (TXIO_MASK|RX_LED_IO)); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, (RXIO_MASK|RX_LED_IO)); + +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_TX, TX_LED_LD, TX_LED_IO); +    boost::this_thread::sleep(boost::posix_time::milliseconds(100)); + +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_TX, \ +            TX_LED_TXRX|TX_LED_LD, TX_LED_IO); +    boost::this_thread::sleep(boost::posix_time::milliseconds(100)); + +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, RX_LED_LD, RX_LED_IO); +    boost::this_thread::sleep(boost::posix_time::milliseconds(100)); + +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, \ +            RX_LED_RX1RX2|RX_LED_LD, RX_LED_IO); +    boost::this_thread::sleep(boost::posix_time::milliseconds(100)); + +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, RX_LED_LD, RX_LED_IO); +    boost::this_thread::sleep(boost::posix_time::milliseconds(100)); + +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, 0, RX_LED_IO); +    boost::this_thread::sleep(boost::posix_time::milliseconds(100)); + +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_TX, TX_LED_LD, TX_LED_IO); +    boost::this_thread::sleep(boost::posix_time::milliseconds(100)); + +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_TX, 0, TX_LED_IO); +    boost::this_thread::sleep(boost::posix_time::milliseconds(100)); + +    //Put LED gpios back in ATR control and update atr +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_TX, (TXIO_MASK|TX_LED_IO)); +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, (RXIO_MASK|RX_LED_IO)); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_TX, (TXIO_MASK|TX_LED_IO)); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, (RXIO_MASK|RX_LED_IO)); +} + diff --git a/host/lib/usrp/dboard/db_sbx_common.hpp b/host/lib/usrp/dboard/db_sbx_common.hpp new file mode 100644 index 000000000..2a0e83115 --- /dev/null +++ b/host/lib/usrp/dboard/db_sbx_common.hpp @@ -0,0 +1,226 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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/>. +// + + + +// Common IO Pins +#define LO_LPF_EN       (1 << 15) +#define SYNTH_CE        (1 << 3) +#define SYNTH_PDBRF     (1 << 2) +#define SYNTH_MUXOUT    (1 << 1)                // INPUT!!! +#define LOCKDET_MASK    (1 << 0)                // INPUT!!! + +// TX IO Pins +#define TRSW            (1 << 14)               // 0 = TX, 1 = RX +#define TX_LED_TXRX     (1 << 7)                // LED for TX Antenna Selection TX/RX +#define TX_LED_LD       (1 << 6)                // LED for TX Lock Detect +#define DIS_POWER_TX    (1 << 5)                // on UNIT_TX, 0 powers up TX +#define TX_ENABLE       (1 << 4)                // on UNIT_TX, 0 disables TX Mixer + +// RX IO Pins +#define LNASW           (1 << 14)               // 0 = TX/RX, 1 = RX2 +#define RX_LED_RX1RX2   (1 << 7)                // LED for RX Antenna Selection RX1/RX2 +#define RX_LED_LD       (1 << 6)                // LED for RX Lock Detect +#define DIS_POWER_RX    (1 << 5)                // on UNIT_RX, 0 powers up RX +#define RX_DISABLE      (1 << 4)                // on UNIT_RX, 1 disables RX Mixer and Baseband + +// RX Attenuator Pins +#define RX_ATTN_SHIFT   8                       // lsb of RX Attenuator Control +#define RX_ATTN_MASK    (63 << RX_ATTN_SHIFT)   // valid bits of RX Attenuator Control + +// TX Attenuator Pins +#define TX_ATTN_SHIFT   8                       // lsb of TX Attenuator Control +#define TX_ATTN_MASK    (63 << TX_ATTN_SHIFT)   // valid bits of TX Attenuator Control + +// Mixer functions +#define TX_MIXER_ENB    (SYNTH_PDBRF|TX_ENABLE) +#define TX_MIXER_DIS    0 + +#define RX_MIXER_ENB    (SYNTH_PDBRF) +#define RX_MIXER_DIS    0 + +// Pin functions +#define TX_LED_IO       (TX_LED_TXRX|TX_LED_LD)     // LED gpio lines, pull down for LED +#define TXIO_MASK       (LO_LPF_EN|TRSW|SYNTH_CE|SYNTH_PDBRF|TX_ATTN_MASK|DIS_POWER_TX|TX_ENABLE) + +#define RX_LED_IO       (RX_LED_RX1RX2|RX_LED_LD)   // LED gpio lines, pull down for LED +#define RXIO_MASK       (LO_LPF_EN|LNASW|SYNTH_CE|SYNTH_PDBRF|RX_ATTN_MASK|DIS_POWER_RX|RX_DISABLE) + +// Power functions +#define TX_POWER_UP     (SYNTH_CE) +#define TX_POWER_DOWN   (DIS_POWER_TX) + +#define RX_POWER_UP     (SYNTH_CE) +#define RX_POWER_DOWN   (DIS_POWER_RX) + +// Antenna constants +#define ANT_TX          TRSW                    //the tx line is transmitting +#define ANT_RX          0                       //the tx line is receiving +#define ANT_TXRX        0                       //the rx line is on txrx +#define ANT_RX2         LNASW                   //the rx line in on rx2 +#define ANT_XX          LNASW                   //dont care how the antenna is set + + +#include <uhd/types/dict.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/log.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/math/special_functions/round.hpp> +#include <boost/thread.hpp> + + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + + +/*********************************************************************** + * The SBX dboard constants + **********************************************************************/ +static const freq_range_t sbx_freq_range(400e6, 4.4e9); + +static const freq_range_t sbx_tx_lo_2dbm = list_of +    (range_t(0.35e9, 0.37e9)) +; + +static const freq_range_t sbx_enable_tx_lo_filter = list_of +    (range_t(0.4e9, 1.5e9)) +; + +static const freq_range_t sbx_enable_rx_lo_filter = list_of +    (range_t(0.4e9, 1.5e9)) +; + +static const std::vector<std::string> sbx_tx_antennas = list_of("TX/RX")("CAL"); + +static const std::vector<std::string> sbx_rx_antennas = list_of("TX/RX")("RX2")("CAL"); + +static const uhd::dict<std::string, gain_range_t> sbx_tx_gain_ranges = map_list_of +    ("PGA0", gain_range_t(0, 31.5, double(0.5))) +; + +static const uhd::dict<std::string, gain_range_t> sbx_rx_gain_ranges = map_list_of +    ("PGA0", gain_range_t(0, 31.5, double(0.5))) +; + +/*********************************************************************** + * The SBX dboard + **********************************************************************/ +class sbx_xcvr : public xcvr_dboard_base{ +public: +    sbx_xcvr(ctor_args_t args); +    ~sbx_xcvr(void); + +protected: + +    uhd::dict<std::string, double> _tx_gains, _rx_gains; +    double       _rx_lo_freq, _tx_lo_freq; +    std::string  _tx_ant, _rx_ant; +    bool _rx_lo_lock_cache, _tx_lo_lock_cache; + +    void set_rx_ant(const std::string &ant); +    void set_tx_ant(const std::string &ant); +    double set_rx_gain(double gain, const std::string &name); +    double set_tx_gain(double gain, const std::string &name); + +    void update_atr(void); + +    /*! +     * Set the LO frequency for the particular dboard unit. +     * \param unit which unit rx or tx +     * \param target_freq the desired frequency in Hz +     * \return the actual frequency in Hz +     */ +    virtual double set_lo_freq(dboard_iface::unit_t unit, double target_freq); + +    /*! +     * Get the lock detect status of the LO. +     * \param unit which unit rx or tx +     * \return true for locked +     */ +    sensor_value_t get_locked(dboard_iface::unit_t unit); + +    /*! +     * Flash the LEDs +     */ +    void flash_leds(void); + +    /*! +     * Version-agnostic ABC that wraps version-specific implementations of the +     * WBX base daughterboard. +     * +     * This class is an abstract base class, and thus is impossible to +     * instantiate. +     */ +    class sbx_versionx { +    public: +        sbx_versionx() {} +        ~sbx_versionx(void) {} + +        virtual double set_lo_freq(dboard_iface::unit_t unit, double target_freq) = 0; +    }; + +    /*! +     * Version 3 of the SBX Daughterboard +     */ +    class sbx_version3 : public sbx_versionx { +    public: +        sbx_version3(sbx_xcvr *_self_sbx_xcvr); +        ~sbx_version3(void); + +        double set_lo_freq(dboard_iface::unit_t unit, double target_freq); + +        /*! This is the registered instance of the wrapper class, sbx_base. */ +        sbx_xcvr *self_base; +    }; + +    /*! +     * Version 4 of the SBX Daughterboard +     * +     * The only difference in the fourth revision is the ADF4351 vs the ADF4350. +     */ +    class sbx_version4 : public sbx_versionx { +    public: +        sbx_version4(sbx_xcvr *_self_sbx_xcvr); +        ~sbx_version4(void); + +        double set_lo_freq(dboard_iface::unit_t unit, double target_freq); + +        /*! This is the registered instance of the wrapper class, sbx_base. */ +        sbx_xcvr *self_base; +    }; + +    /*! +     * Handle to the version-specific implementation of the SBX. +     * +     * Since many of this class's functions are dependent on the version of the +     * SBX board, this class will instantiate an object of the appropriate +     * sbx_version* subclass, and invoke any relevant functions through that +     * object.  This pointer is set to the proper object at construction time. +     */ +    typedef boost::shared_ptr<sbx_versionx> sbx_versionx_sptr; +    sbx_versionx_sptr db_actual; +}; + diff --git a/host/lib/usrp/dboard/db_sbx_version3.cpp b/host/lib/usrp/dboard/db_sbx_version3.cpp new file mode 100644 index 000000000..040bef12f --- /dev/null +++ b/host/lib/usrp/dboard/db_sbx_version3.cpp @@ -0,0 +1,188 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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 "adf4350_regs.hpp" +#include "db_sbx_common.hpp" + + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +/*********************************************************************** + * Structors + **********************************************************************/ +sbx_xcvr::sbx_version3::sbx_version3(sbx_xcvr *_self_sbx_xcvr) { +    //register the handle to our base SBX class +    self_base = _self_sbx_xcvr; +} + +sbx_xcvr::sbx_version3::~sbx_version3(void){ +    /* NOP */ +} + + +/*********************************************************************** + * Tuning + **********************************************************************/ +double sbx_xcvr::sbx_version3::set_lo_freq(dboard_iface::unit_t unit, double target_freq) { +    UHD_LOGV(often) << boost::format( +        "SBX tune: target frequency %f Mhz" +    ) % (target_freq/1e6) << std::endl; + +    //clip the input +    target_freq = sbx_freq_range.clip(target_freq); + +    //map prescaler setting to mininmum integer divider (N) values (pg.18 prescaler) +    static const uhd::dict<int, int> prescaler_to_min_int_div = map_list_of +        (0,23) //adf4350_regs_t::PRESCALER_4_5 +        (1,75) //adf4350_regs_t::PRESCALER_8_9 +    ; + +    //map rf divider select output dividers to enums +    static const uhd::dict<int, adf4350_regs_t::rf_divider_select_t> rfdivsel_to_enum = map_list_of +        (1,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV1) +        (2,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV2) +        (4,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV4) +        (8,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV8) +        (16, adf4350_regs_t::RF_DIVIDER_SELECT_DIV16) +    ; + +    double actual_freq, pfd_freq; +    double ref_freq = self_base->get_iface()->get_clock_rate(unit); +    int R=0, BS=0, N=0, FRAC=0, MOD=0; +    int RFdiv = 1; +    adf4350_regs_t::reference_divide_by_2_t T     = adf4350_regs_t::REFERENCE_DIVIDE_BY_2_DISABLED; +    adf4350_regs_t::reference_doubler_t     D     = adf4350_regs_t::REFERENCE_DOUBLER_DISABLED;     + +    //Reference doubler for 50% duty cycle +    // if ref_freq < 12.5MHz enable regs.reference_divide_by_2 +    if(ref_freq <= 12.5e6) D = adf4350_regs_t::REFERENCE_DOUBLER_ENABLED; + +    //increase RF divider until acceptable VCO frequency +    double vco_freq = target_freq; +    while (vco_freq < 2.2e9) { +        vco_freq *= 2; +        RFdiv *= 2; +    } + +    //use 8/9 prescaler for vco_freq > 3 GHz (pg.18 prescaler) +    adf4350_regs_t::prescaler_t prescaler = target_freq > 3e9 ? adf4350_regs_t::PRESCALER_8_9 : adf4350_regs_t::PRESCALER_4_5; + +    /* +     * The goal here is to loop though possible R dividers, +     * band select clock dividers, N (int) dividers, and FRAC  +     * (frac) dividers. +     * +     * Calculate the N and F dividers for each set of values. +     * The loop exits when it meets all of the constraints. +     * The resulting loop values are loaded into the registers. +     * +     * from pg.21 +     * +     * f_pfd = f_ref*(1+D)/(R*(1+T)) +     * f_vco = (N + (FRAC/MOD))*f_pfd +     *    N = f_vco/f_pfd - FRAC/MOD = f_vco*((R*(T+1))/(f_ref*(1+D))) - FRAC/MOD +     * f_rf = f_vco/RFdiv) +     * f_actual = f_rf/2 +     */ +    for(R = 1; R <= 1023; R+=1){ +        //PFD input frequency = f_ref/R ... ignoring Reference doubler/divide-by-2 (D & T) +        pfd_freq = ref_freq*(1+D)/(R*(1+T)); + +        //keep the PFD frequency at or below 25MHz (Loop Filter Bandwidth) +        if (pfd_freq > 25e6) continue; + +        //ignore fractional part of tuning +        N = int(std::floor(target_freq/pfd_freq)); + +        //keep N > minimum int divider requirement +        if (N < prescaler_to_min_int_div[prescaler]) continue; + +        for(BS=1; BS <= 255; BS+=1){ +            //keep the band select frequency at or below 100KHz +            //constraint on band select clock +            if (pfd_freq/BS > 100e3) continue; +            goto done_loop; +        } +    } done_loop: + +    //Fractional-N calculation +    MOD = 4095; //max fractional accuracy +    FRAC = int((target_freq/pfd_freq - N)*MOD); + +    //Reference divide-by-2 for 50% duty cycle +    // if R even, move one divide by 2 to to regs.reference_divide_by_2 +    if(R % 2 == 0){ +        T = adf4350_regs_t::REFERENCE_DIVIDE_BY_2_ENABLED; +        R /= 2; +    } + +    //actual frequency calculation +    actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))); + +    UHD_LOGV(often) +        << boost::format("SBX Intermediates: ref=%0.2f, outdiv=%f, fbdiv=%f") % (ref_freq*(1+int(D))/(R*(1+int(T)))) % double(RFdiv*2) % double(N + double(FRAC)/double(MOD)) << std::endl +        << boost::format("SBX tune: R=%d, BS=%d, N=%d, FRAC=%d, MOD=%d, T=%d, D=%d, RFdiv=%d" +            ) % R % BS % N % FRAC % MOD % T % D % RFdiv << std::endl +        << boost::format("SBX Frequencies (MHz): REQ=%0.2f, ACT=%0.2f, VCO=%0.2f, PFD=%0.2f, BAND=%0.2f" +            ) % (target_freq/1e6) % (actual_freq/1e6) % (vco_freq/1e6) % (pfd_freq/1e6) % (pfd_freq/BS/1e6) << std::endl; + +    //load the register values +    adf4350_regs_t regs; + +    if ((unit == dboard_iface::UNIT_TX) and (actual_freq == sbx_tx_lo_2dbm.clip(actual_freq)))  +        regs.output_power = adf4350_regs_t::OUTPUT_POWER_2DBM; +    else +        regs.output_power = adf4350_regs_t::OUTPUT_POWER_5DBM; + +    regs.frac_12_bit = FRAC; +    regs.int_16_bit = N; +    regs.mod_12_bit = MOD; +    regs.clock_divider_12_bit = std::max(1, int(std::ceil(400e-6*pfd_freq/MOD))); +    regs.feedback_select = adf4350_regs_t::FEEDBACK_SELECT_DIVIDED; +    regs.clock_div_mode = adf4350_regs_t::CLOCK_DIV_MODE_RESYNC_ENABLE; +    regs.prescaler = prescaler; +    regs.r_counter_10_bit = R; +    regs.reference_divide_by_2 = T; +    regs.reference_doubler = D; +    regs.band_select_clock_div = BS; +    UHD_ASSERT_THROW(rfdivsel_to_enum.has_key(RFdiv)); +    regs.rf_divider_select = rfdivsel_to_enum[RFdiv]; + +    //write the registers +    //correct power-up sequence to write registers (5, 4, 3, 2, 1, 0) +    int addr; + +    for(addr=5; addr>=0; addr--){ +        UHD_LOGV(often) << boost::format( +            "SBX SPI Reg (0x%02x): 0x%08x" +        ) % addr % regs.get_reg(addr) << std::endl; +        self_base->get_iface()->write_spi( +            unit, spi_config_t::EDGE_RISE, +            regs.get_reg(addr), 32 +        ); +    } + +    //return the actual frequency +    UHD_LOGV(often) << boost::format( +        "SBX tune: actual frequency %f Mhz" +    ) % (actual_freq/1e6) << std::endl; +    return actual_freq; +} + diff --git a/host/lib/usrp/dboard/db_sbx_version4.cpp b/host/lib/usrp/dboard/db_sbx_version4.cpp new file mode 100644 index 000000000..f091caab7 --- /dev/null +++ b/host/lib/usrp/dboard/db_sbx_version4.cpp @@ -0,0 +1,191 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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 "adf4351_regs.hpp" +#include "db_sbx_common.hpp" + + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +/*********************************************************************** + * Structors + **********************************************************************/ +sbx_xcvr::sbx_version4::sbx_version4(sbx_xcvr *_self_sbx_xcvr) { +    //register the handle to our base SBX class +    self_base = _self_sbx_xcvr; +} + + +sbx_xcvr::sbx_version4::~sbx_version4(void){ +    /* NOP */ +} + + +/*********************************************************************** + * Tuning + **********************************************************************/ +double sbx_xcvr::sbx_version4::set_lo_freq(dboard_iface::unit_t unit, double target_freq) { +    UHD_LOGV(often) << boost::format( +        "SBX tune: target frequency %f Mhz" +    ) % (target_freq/1e6) << std::endl; + +    //clip the input +    target_freq = sbx_freq_range.clip(target_freq); + +    //map prescaler setting to mininmum integer divider (N) values (pg.18 prescaler) +    static const uhd::dict<int, int> prescaler_to_min_int_div = map_list_of +        (0,23) //adf4351_regs_t::PRESCALER_4_5 +        (1,75) //adf4351_regs_t::PRESCALER_8_9 +    ; + +    //map rf divider select output dividers to enums +    static const uhd::dict<int, adf4351_regs_t::rf_divider_select_t> rfdivsel_to_enum = map_list_of +        (1,  adf4351_regs_t::RF_DIVIDER_SELECT_DIV1) +        (2,  adf4351_regs_t::RF_DIVIDER_SELECT_DIV2) +        (4,  adf4351_regs_t::RF_DIVIDER_SELECT_DIV4) +        (8,  adf4351_regs_t::RF_DIVIDER_SELECT_DIV8) +        (16, adf4351_regs_t::RF_DIVIDER_SELECT_DIV16) +        (32, adf4351_regs_t::RF_DIVIDER_SELECT_DIV32) +        (64, adf4351_regs_t::RF_DIVIDER_SELECT_DIV64) +    ; + +    double actual_freq, pfd_freq; +    double ref_freq = self_base->get_iface()->get_clock_rate(unit); +    int R=0, BS=0, N=0, FRAC=0, MOD=0; +    int RFdiv = 1; +    adf4351_regs_t::reference_divide_by_2_t T     = adf4351_regs_t::REFERENCE_DIVIDE_BY_2_DISABLED; +    adf4351_regs_t::reference_doubler_t     D     = adf4351_regs_t::REFERENCE_DOUBLER_DISABLED;     + +    //Reference doubler for 50% duty cycle +    // if ref_freq < 12.5MHz enable regs.reference_divide_by_2 +    if(ref_freq <= 12.5e6) D = adf4351_regs_t::REFERENCE_DOUBLER_ENABLED; + +    //increase RF divider until acceptable VCO frequency +    double vco_freq = target_freq; +    while (vco_freq < 2.2e9) { +        vco_freq *= 2; +        RFdiv *= 2; +    } + +    //use 8/9 prescaler for vco_freq > 3 GHz (pg.18 prescaler) +    adf4351_regs_t::prescaler_t prescaler = target_freq > 3e9 ? adf4351_regs_t::PRESCALER_8_9 : adf4351_regs_t::PRESCALER_4_5; + +    /* +     * The goal here is to loop though possible R dividers, +     * band select clock dividers, N (int) dividers, and FRAC  +     * (frac) dividers. +     * +     * Calculate the N and F dividers for each set of values. +     * The loop exits when it meets all of the constraints. +     * The resulting loop values are loaded into the registers. +     * +     * from pg.21 +     * +     * f_pfd = f_ref*(1+D)/(R*(1+T)) +     * f_vco = (N + (FRAC/MOD))*f_pfd +     *    N = f_vco/f_pfd - FRAC/MOD = f_vco*((R*(T+1))/(f_ref*(1+D))) - FRAC/MOD +     * f_rf = f_vco/RFdiv) +     * f_actual = f_rf/2 +     */ +    for(R = 1; R <= 1023; R+=1){ +        //PFD input frequency = f_ref/R ... ignoring Reference doubler/divide-by-2 (D & T) +        pfd_freq = ref_freq*(1+D)/(R*(1+T)); + +        //keep the PFD frequency at or below 25MHz (Loop Filter Bandwidth) +        if (pfd_freq > 25e6) continue; + +        //ignore fractional part of tuning +        N = int(std::floor(vco_freq/pfd_freq)); + +        //keep N > minimum int divider requirement +        if (N < prescaler_to_min_int_div[prescaler]) continue; + +        for(BS=1; BS <= 255; BS+=1){ +            //keep the band select frequency at or below 100KHz +            //constraint on band select clock +            if (pfd_freq/BS > 100e3) continue; +            goto done_loop; +        } +    } done_loop: + +    //Fractional-N calculation +    MOD = 4095; //max fractional accuracy +    FRAC = int((target_freq/pfd_freq - N)*MOD); + +    //Reference divide-by-2 for 50% duty cycle +    // if R even, move one divide by 2 to to regs.reference_divide_by_2 +    if(R % 2 == 0){ +        T = adf4351_regs_t::REFERENCE_DIVIDE_BY_2_ENABLED; +        R /= 2; +    } + +    //actual frequency calculation +    actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))); + +    UHD_LOGV(often) +        << boost::format("SBX Intermediates: ref=%0.2f, outdiv=%f, fbdiv=%f") % (ref_freq*(1+int(D))/(R*(1+int(T)))) % double(RFdiv*2) % double(N + double(FRAC)/double(MOD)) << std::endl +        << boost::format("SBX tune: R=%d, BS=%d, N=%d, FRAC=%d, MOD=%d, T=%d, D=%d, RFdiv=%d" +            ) % R % BS % N % FRAC % MOD % T % D % RFdiv << std::endl +        << boost::format("SBX Frequencies (MHz): REQ=%0.2f, ACT=%0.2f, VCO=%0.2f, PFD=%0.2f, BAND=%0.2f" +            ) % (target_freq/1e6) % (actual_freq/1e6) % (vco_freq/1e6) % (pfd_freq/1e6) % (pfd_freq/BS/1e6) << std::endl; + +    //load the register values +    adf4351_regs_t regs; + +    if ((unit == dboard_iface::UNIT_TX) and (actual_freq == sbx_tx_lo_2dbm.clip(actual_freq)))  +        regs.output_power = adf4351_regs_t::OUTPUT_POWER_2DBM; +    else +        regs.output_power = adf4351_regs_t::OUTPUT_POWER_5DBM; + +    regs.frac_12_bit = FRAC; +    regs.int_16_bit = N; +    regs.mod_12_bit = MOD; +    regs.clock_divider_12_bit = std::max(1, int(std::ceil(400e-6*pfd_freq/MOD))); +    regs.feedback_select = adf4351_regs_t::FEEDBACK_SELECT_DIVIDED; +    regs.clock_div_mode = adf4351_regs_t::CLOCK_DIV_MODE_RESYNC_ENABLE; +    regs.prescaler = prescaler; +    regs.r_counter_10_bit = R; +    regs.reference_divide_by_2 = T; +    regs.reference_doubler = D; +    regs.band_select_clock_div = BS; +    UHD_ASSERT_THROW(rfdivsel_to_enum.has_key(RFdiv)); +    regs.rf_divider_select = rfdivsel_to_enum[RFdiv]; + +    //write the registers +    //correct power-up sequence to write registers (5, 4, 3, 2, 1, 0) +    int addr; + +    for(addr=5; addr>=0; addr--){ +        UHD_LOGV(often) << boost::format( +            "SBX SPI Reg (0x%02x): 0x%08x" +        ) % addr % regs.get_reg(addr) << std::endl; +        self_base->get_iface()->write_spi( +            unit, spi_config_t::EDGE_RISE, +            regs.get_reg(addr), 32 +        ); +    } + +    //return the actual frequency +    UHD_LOGV(often) << boost::format( +        "SBX tune: actual frequency %f Mhz" +    ) % (actual_freq/1e6) << std::endl; +    return actual_freq; +} + diff --git a/host/lib/usrp/dboard/db_tvrx.cpp b/host/lib/usrp/dboard/db_tvrx.cpp new file mode 100644 index 000000000..edee46cd5 --- /dev/null +++ b/host/lib/usrp/dboard/db_tvrx.cpp @@ -0,0 +1,411 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +// No RX IO Pins Used + +// RX IO Functions + +//ADC/DAC functions: +//DAC 1: RF AGC +//DAC 2: IF AGC + +//min freq: 50e6 +//max freq: 860e6 +//gain range: [0:1dB:115dB] + +#include <uhd/utils/log.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/thread.hpp> +#include <boost/array.hpp> +#include <boost/math/special_functions/round.hpp> +#include <utility> +#include <cmath> +#include <cfloat> +#include <limits> +#include <tuner_4937di5_regs.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +/*********************************************************************** + * The tvrx constants + **********************************************************************/ +static const freq_range_t tvrx_freq_range(50e6, 860e6); + +static const std::vector<std::string> tvrx_antennas = list_of("RX"); + +static const uhd::dict<std::string, freq_range_t> tvrx_freq_ranges = map_list_of +    ("VHFLO", freq_range_t(50e6, 158e6)) +    ("VHFHI", freq_range_t(158e6, 454e6)) +    ("UHF"  , freq_range_t(454e6, 860e6)) +; + +static const boost::array<double, 17> vhflo_gains_db = +    {{-6.00000, -6.00000, -6.00000, -4.00000, 0.00000, +     5.00000, 10.00000, 17.40000, 26.30000, 36.00000, +     43.00000, 48.00000, 49.50000, 50.10000, 50.30000, +     50.30000, 50.30000}}; + +static const boost::array<double, 17> vhfhi_gains_db = +    {{-13.3000,  -13.3000,  -13.3000,   -1.0000,    7.7000, +    11.0000,   14.7000,   19.3000,   26.1000,   36.0000, +    42.7000,   46.0000,   47.0000,   47.8000,   48.2000, +    48.2000,   48.2000}}; + +static const boost::array<double, 17> uhf_gains_db = +    {{-8.0000,   -8.0000,   -7.0000,    4.0000,   10.2000, +     14.5000,   17.5000,   20.0000,   24.5000,   30.8000, +     37.0000,   39.8000,   40.7000,   41.6000,   42.6000, +     43.2000,   43.8000}}; + +static const boost::array<double, 17> tvrx_if_gains_db = +    {{-1.50000,   -1.50000,   -1.50000,   -1.00000,    0.20000, +     2.10000,    4.30000,    6.40000,    9.00000,   12.00000, +     14.80000,   18.20000,   26.10000,   32.50000,  32.50000, +     32.50000,   32.50000}}; + +//gain linearization data +//this is from the datasheet and is dB vs. volts (below) +//i tried to curve fit this, but it's really just so nonlinear that you'd +//need dang near as many coefficients as to just map it like this and interp. +//these numbers are culled from the 4937DI5 datasheet and are probably totally inaccurate +//but if it's better than the old linear fit i'm happy +static const uhd::dict<std::string, boost::array<double, 17> > tvrx_rf_gains_db = map_list_of +    ("VHFLO", vhflo_gains_db) +    ("VHFHI", vhfhi_gains_db) +    ("UHF"  , uhf_gains_db) +; + +//sample voltages for the above points +static const boost::array<double, 17> tvrx_gains_volts = +    {{0.8, 1.0, 1.2, 1.4, 1.6, 1.8, 2.0, 2.2, 2.4, 2.6, 2.8, 3.0, 3.2, 3.4, 3.6, 3.8, 4.0}}; + +static uhd::dict<std::string, gain_range_t> get_tvrx_gain_ranges(void) { +    double rfmax = 0.0, rfmin = FLT_MAX; +    BOOST_FOREACH(const std::string range, tvrx_rf_gains_db.keys()) { +        double my_max = tvrx_rf_gains_db[range].back(); //we're assuming it's monotonic +        double my_min = tvrx_rf_gains_db[range].front(); //if it's not this is wrong wrong wrong +        if(my_max > rfmax) rfmax = my_max; +        if(my_min < rfmin) rfmin = my_min; +    } + +    double ifmin = tvrx_if_gains_db.front(); +    double ifmax = tvrx_if_gains_db.back(); + +    return map_list_of +        ("RF", gain_range_t(rfmin, rfmax, (rfmax-rfmin)/4096.0)) +        ("IF", gain_range_t(ifmin, ifmax, (ifmax-ifmin)/4096.0)) +    ; +} + +static const double opamp_gain = 1.22; //onboard DAC opamp gain +static const double tvrx_if_freq = 43.75e6; //IF freq of TVRX module +static const boost::uint16_t reference_divider = 640; //clock reference divider to use +static const double reference_freq = 4.0e6; + +/*********************************************************************** + * The tvrx dboard class + **********************************************************************/ +class tvrx : public rx_dboard_base{ +public: +    tvrx(ctor_args_t args); +    ~tvrx(void); + +private: +    uhd::dict<std::string, double> _gains; +    double _lo_freq; +    tuner_4937di5_regs_t _tuner_4937di5_regs; +    boost::uint8_t _tuner_4937di5_addr(void){ +        return (this->get_iface()->get_special_props().mangle_i2c_addrs)? 0x61 : 0x60; //ok really? we could rename that call +    }; + +    double set_gain(double gain, const std::string &name); +    double set_freq(double freq); + +    void update_regs(void){ +        byte_vector_t regs_vector(4); + +        //get the register data +        for(int i=0; i<4; i++){ +            regs_vector[i] = _tuner_4937di5_regs.get_reg(i); +            UHD_LOGV(often) << boost::format( +                "tvrx: send reg 0x%02x, value 0x%04x" +            ) % int(i) % int(regs_vector[i]) << std::endl; +        } + +        //send the data +        this->get_iface()->write_i2c( +            _tuner_4937di5_addr(), regs_vector +        ); +    } + +}; + +/*********************************************************************** + * Register the tvrx dboard + **********************************************************************/ +static dboard_base::sptr make_tvrx(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new tvrx(args)); +} + +UHD_STATIC_BLOCK(reg_tvrx_dboard){ +    //register the factory function for the rx dbid +    dboard_manager::register_dboard(0x0040, &make_tvrx, "TVRX"); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +tvrx::tvrx(ctor_args_t args) : rx_dboard_base(args){ +    //////////////////////////////////////////////////////////////////// +    // Register properties +    //////////////////////////////////////////////////////////////////// +    this->get_rx_subtree()->create<std::string>("name") +        .set("TVRX"); +    this->get_rx_subtree()->create<int>("sensors"); //phony property so this dir exists +    BOOST_FOREACH(const std::string &name, get_tvrx_gain_ranges().keys()){ +        this->get_rx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&tvrx::set_gain, this, _1, name)); +        this->get_rx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(get_tvrx_gain_ranges()[name]); +    } +    this->get_rx_subtree()->create<double>("freq/value") +        .coerce(boost::bind(&tvrx::set_freq, this, _1)); +    this->get_rx_subtree()->create<meta_range_t>("freq/range") +        .set(tvrx_freq_range); +    this->get_rx_subtree()->create<std::string>("antenna/value") +        .set(tvrx_antennas.at(0)); +    this->get_rx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(tvrx_antennas); +    this->get_rx_subtree()->create<std::string>("connection") +        .set("I"); +    this->get_rx_subtree()->create<bool>("enabled") +        .set(true); //always enabled +    this->get_rx_subtree()->create<bool>("use_lo_offset") +        .set(false); +    this->get_rx_subtree()->create<double>("bandwidth/value") +        .set(6.0e6); +    this->get_rx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(6.0e6, 6.0e6)); + +    //enable only the clocks we need +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_RX, true); + +    //set the gpio directions and atr controls (identically) +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, 0x0); // All unused in atr +    if (this->get_iface()->get_special_props().soft_clock_divider){ +        this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, 0x1); // GPIO0 is clock +    } +    else{ +        this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, 0x0); // All Inputs +    } + +    //send initial register settings if necessary + +    //set default freq +    _lo_freq = tvrx_freq_range.start() + tvrx_if_freq; //init _lo_freq to a sane default +    this->get_rx_subtree()->access<double>("freq/value").set(tvrx_freq_range.start()); + +    //set default gains +    BOOST_FOREACH(const std::string &name, get_tvrx_gain_ranges().keys()){ +        this->get_rx_subtree()->access<double>("gains/"+name+"/value") +            .set(get_tvrx_gain_ranges()[name].start()); +    } +} + +tvrx::~tvrx(void){ +} + +/*! Return a string corresponding to the relevant band + * \param freq the frequency of interest + * \return a string corresponding to the band + */ + +static std::string get_band(double freq) { +    BOOST_FOREACH(const std::string &band, tvrx_freq_ranges.keys()) { +        if(freq >= tvrx_freq_ranges[band].start() && freq <= tvrx_freq_ranges[band].stop()){ +            UHD_LOGV(often) << "Band: " << band << std::endl; +            return band; +        } +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +/*! + * Execute a linear interpolation to find the voltage corresponding to a desired gain + * \param gain the desired gain in dB + * \param db_vector the vector of dB readings + * \param volts_vector the corresponding vector of voltages db_vector was sampled at + * \return a voltage to feed the TVRX analog gain + */ + +static double gain_interp(double gain, boost::array<double, 17> db_vector, boost::array<double, 17> volts_vector) { +    double volts; +    gain = uhd::clip<double>(gain, db_vector.front(), db_vector.back()); //let's not get carried away here + +    boost::uint8_t gain_step = 0; +    //find which bin we're in +    for(size_t i = 0; i < db_vector.size()-1; i++) { +        if(gain >= db_vector[i] && gain <= db_vector[i+1]) gain_step = i; +    } + +    //find the current slope for linear interpolation +    double slope = (volts_vector[gain_step + 1] - volts_vector[gain_step]) +                / (db_vector[gain_step + 1] - db_vector[gain_step]); + +    //the problem here is that for gains approaching the maximum, the voltage slope becomes infinite +    //i.e., a small change in gain requires an infinite change in voltage +    //to cope, we limit the slope + +    if(slope == std::numeric_limits<double>::infinity()) +        return volts_vector[gain_step]; + +    //use the volts per dB slope to find the final interpolated voltage +    volts = volts_vector[gain_step] + (slope * (gain - db_vector[gain_step])); + +    UHD_LOGV(often) << "Gain interp: gain: " << gain << ", gain_step: " << int(gain_step) << ", slope: " << slope << ", volts: " << volts << std::endl; + +    return volts; +} + +/*! + * Convert a requested gain for the RF gain into a DAC voltage. + * The gain passed into the function will be set to the actual value. + * \param gain the requested gain in dB + * \return dac voltage value + */ + +static double rf_gain_to_voltage(double gain, double lo_freq){ +    //clip the input +    gain = get_tvrx_gain_ranges()["RF"].clip(gain); + +    //first we need to find out what band we're in, because gains are different across different bands +    std::string band = get_band(lo_freq - tvrx_if_freq); + +    //this is the voltage at the TVRX gain input +    double gain_volts = gain_interp(gain, tvrx_rf_gains_db[band], tvrx_gains_volts); +    //this is the voltage at the USRP DAC output +    double dac_volts = gain_volts / opamp_gain; + +    dac_volts = uhd::clip<double>(dac_volts, 0.0, 3.3); + +    UHD_LOGV(often) << boost::format( +        "tvrx RF AGC gain: %f dB, dac_volts: %f V" +    ) % gain % dac_volts << std::endl; + +    return dac_volts; +} + +/*! + * Convert a requested gain for the IF gain into a DAC voltage. + * The gain passed into the function will be set to the actual value. + * \param gain the requested gain in dB + * \return dac voltage value + */ + +static double if_gain_to_voltage(double gain){ +    //clip the input +    gain = get_tvrx_gain_ranges()["IF"].clip(gain); + +    double gain_volts = gain_interp(gain, tvrx_if_gains_db, tvrx_gains_volts); +    double dac_volts = gain_volts / opamp_gain; + +    dac_volts = uhd::clip<double>(dac_volts, 0.0, 3.3); + +    UHD_LOGV(often) << boost::format( +        "tvrx IF AGC gain: %f dB, dac_volts: %f V" +    ) % gain % dac_volts << std::endl; + +    return dac_volts; +} + +double tvrx::set_gain(double gain, const std::string &name){ +    assert_has(get_tvrx_gain_ranges().keys(), name, "tvrx gain name"); +    if (name == "RF"){ +        this->get_iface()->write_aux_dac(dboard_iface::UNIT_RX, dboard_iface::AUX_DAC_B, rf_gain_to_voltage(gain, _lo_freq)); +    } +    else if(name == "IF"){ +        this->get_iface()->write_aux_dac(dboard_iface::UNIT_RX, dboard_iface::AUX_DAC_A, if_gain_to_voltage(gain)); +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    _gains[name] = gain; + +    return gain; +} + +/*! + * Set the tuner to center the desired frequency at 43.75MHz + * \param freq the requested frequency + */ + +double tvrx::set_freq(double freq) { +    freq = tvrx_freq_range.clip(freq); +    std::string prev_band = get_band(_lo_freq - tvrx_if_freq); +    std::string new_band = get_band(freq); + +    double target_lo_freq = freq + tvrx_if_freq; //the desired LO freq for high-side mixing +    double f_ref = reference_freq / double(reference_divider); //your tuning step size + +    int divisor = int((target_lo_freq + (f_ref * 4.0)) / (f_ref * 8)); //the divisor we'll use +    double actual_lo_freq = (f_ref * 8 * divisor); //the LO freq we'll actually get + +    if((divisor & ~0x7fff)) UHD_THROW_INVALID_CODE_PATH(); + +    //now we update the registers +    _tuner_4937di5_regs.db1 = (divisor >> 8) & 0xff; +    _tuner_4937di5_regs.db2 = divisor & 0xff; + +    if(new_band == "VHFLO") _tuner_4937di5_regs.bandsel = tuner_4937di5_regs_t::BANDSEL_VHFLO; +    else if(new_band == "VHFHI") _tuner_4937di5_regs.bandsel = tuner_4937di5_regs_t::BANDSEL_VHFHI; +    else if(new_band == "UHF") _tuner_4937di5_regs.bandsel = tuner_4937di5_regs_t::BANDSEL_UHF; +    else UHD_THROW_INVALID_CODE_PATH(); + +    _tuner_4937di5_regs.power = tuner_4937di5_regs_t::POWER_OFF; +    update_regs(); + +    //ok don't forget to reset RF gain here if the new band != the old band +    //we do this because the gains are different for different band settings +    //not FAR off, but we do this to be consistent +    if(prev_band != new_band) set_gain(_gains["RF"], "RF"); + +    UHD_LOGV(often) << boost::format("set_freq: target LO: %f f_ref: %f divisor: %i actual LO: %f") % target_lo_freq % f_ref % divisor % actual_lo_freq << std::endl; + +    _lo_freq = actual_lo_freq; //for rx props + +    //Check the the IF if larger than the dsp rate and apply a corrective adjustment +    //so that the cordic will be tuned to a possible rate within its range. +    const double codec_rate = this->get_iface()->get_codec_rate(dboard_iface::UNIT_RX); +    if (tvrx_if_freq >= codec_rate/2){ +        return _lo_freq - codec_rate; +    } + +    return _lo_freq; +} diff --git a/host/lib/usrp/dboard/db_tvrx2.cpp b/host/lib/usrp/dboard/db_tvrx2.cpp new file mode 100644 index 000000000..0bfa5229a --- /dev/null +++ b/host/lib/usrp/dboard/db_tvrx2.cpp @@ -0,0 +1,1844 @@ +// +// Copyright 2010,2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +// Common IO Pins +#define REFCLOCK_DIV_MASK    ((1 << 8)|(1 << 9)|(1 << 10))    // Three GPIO lines to CPLD for Clock Divisor Selection +#define REFCLOCK_DIV8        ((1 << 8)|(1 << 9)|(1 << 10))    // GPIO to set clock div8 mode +#define REFCLOCK_DIV7        ((0 << 8)|(1 << 9)|(1 << 10))    // GPIO to set clock div7 mode +#define REFCLOCK_DIV6        ((1 << 8)|(0 << 9)|(1 << 10))    // GPIO to set clock div6 mode +#define REFCLOCK_DIV5        ((0 << 8)|(0 << 9)|(1 << 10))    // GPIO to set clock div5 mode +#define REFCLOCK_DIV4        ((1 << 8)|(1 <<9))               // GPIO to set clock div4 mode +#define REFCLOCK_DIV3        (1 <<9)                          // GPIO to set clock div3 mode +#define REFCLOCK_DIV2        (1 <<8)                          // GPIO to set clock div2 mode +#define REFCLOCK_DIV1        ((0 << 8)|(0 << 9)|(0 << 10))    // GPIO to set clock div1 mode + +// RX1 IO Pins +#define RX1_MASTERSYNC  (1 << 3)                // MASTERSYNC Signal for Slave Tuner Coordination +#define RX1_FREEZE      (1 << 2)                // FREEZE Signal for Slave Tuner Coordination +#define RX1_IRQ         (1 << 1)                // IRQ Signals TDA18272HNM State Machine Completion +#define RX1_VSYNC       (1 << 0)                // VSYNC Pulse for AGC Holdoff + +// RX2 IO Pins +#define RX2_MASTERSYNC  (1 << 7)                // MASTERSYNC Signal for Slave Tuner Coordination +#define RX2_FREEZE      (1 << 6)                // FREEZE Signal for Slave Tuner Coordination +#define RX2_IRQ         (1 << 5)                // IRQ Signals TDA18272HNM State Machine Completion +#define RX2_VSYNC       (1 << 4)                // VSYNC Pulse for AGC Holdoff + +// Pin functions +#define RX1_OUTPUT_MASK (0) +#define RX1_INPUT_MASK  (RX1_VSYNC|RX1_MASTERSYNC|RX1_FREEZE|RX1_IRQ) + +#define RX2_OUTPUT_MASK (0) +#define RX2_INPUT_MASK  (RX2_VSYNC|RX2_MASTERSYNC|RX2_FREEZE|RX2_IRQ) + +#define OUTPUT_MASK     (RX1_OUTPUT_MASK|RX2_OUTPUT_MASK|REFCLOCK_DIV_MASK) +#define INPUT_MASK      (RX1_INPUT_MASK|RX2_INPUT_MASK) + + +#include "tda18272hnm_regs.hpp" +#include <uhd/utils/static.hpp> +#include <uhd/utils/log.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/utils/safe_call.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/thread.hpp> +#include <boost/array.hpp> +#include <boost/math/special_functions/round.hpp> +#include <utility> +#include <cmath> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +/*********************************************************************** + * The TVRX2 types + **********************************************************************/ +struct tvrx2_tda18272_rfcal_result_t { +    boost::int8_t    delta_c; +    boost::int8_t    c_offset; +    tvrx2_tda18272_rfcal_result_t(void): delta_c(0), c_offset(0){} +}; + +struct tvrx2_tda18272_rfcal_coeffs_t  { +    boost::uint8_t   cal_number; +    boost::int32_t   RF_A1; +    boost::int32_t   RF_B1; +    tvrx2_tda18272_rfcal_coeffs_t(void): cal_number(0), RF_A1(0), RF_B1(0) {} +    tvrx2_tda18272_rfcal_coeffs_t(boost::uint32_t num): RF_A1(0), RF_B1(0) { cal_number = num; } +}; + +struct tvrx2_tda18272_cal_map_t { +    boost::array<boost::uint32_t, 4>  cal_freq; +    boost::array<boost::uint8_t, 4>   c_offset; +    tvrx2_tda18272_cal_map_t(boost::array<boost::uint32_t, 4> freqs, boost::array<boost::uint8_t, 4> offsets) +        { cal_freq = freqs; c_offset = offsets; } +}; + +struct tvrx2_tda18272_freq_map_t { +    boost::uint32_t  rf_max; +    boost::uint8_t   c_prog; +    boost::uint8_t   gain_taper; +    boost::uint8_t   rf_band; +    tvrx2_tda18272_freq_map_t( boost::uint32_t max, boost::uint8_t c, boost::uint8_t taper, boost::uint8_t band) +        { rf_max = max; c_prog = c; gain_taper = taper; rf_band = band; } +}; + +/*********************************************************************** + * The TVRX2 constants + **********************************************************************/ + +static const boost::array<freq_range_t, 4> tvrx2_tda18272_rf_bands = list_of +    ( freq_range_t(  44.056e6, 144.408e6) ) +    ( freq_range_t( 145.432e6, 361.496e6) ) +    ( freq_range_t( 365.592e6, 618.520e6) ) +    ( freq_range_t( 619.544e6, 865.304e6) ) +; + +#define TVRX2_TDA18272_FREQ_MAP_ENTRIES (565) + +static const uhd::dict<boost::uint32_t, tvrx2_tda18272_cal_map_t> tvrx2_tda18272_cal_map = map_list_of +    (  0, tvrx2_tda18272_cal_map_t( list_of( 44032000)( 48128000)( 52224000)( 56320000), list_of(15)( 0)(10)(17) ) ) +    (  1, tvrx2_tda18272_cal_map_t( list_of( 84992000)( 89088000)( 93184000)( 97280000), list_of( 1)( 0)(-2)( 3) ) ) +    (  2, tvrx2_tda18272_cal_map_t( list_of(106496000)(111616000)(115712000)(123904000), list_of( 0)(-1)( 1)( 2) ) ) +    (  3, tvrx2_tda18272_cal_map_t( list_of(161792000)(165888000)(169984000)(174080000), list_of( 3)( 0)( 1)( 2) ) ) +    (  4, tvrx2_tda18272_cal_map_t( list_of(224256000)(228352000)(232448000)(235520000), list_of( 3)( 0)( 1)( 2) ) ) +    (  5, tvrx2_tda18272_cal_map_t( list_of(301056000)(312320000)(322560000)(335872000), list_of( 0)(-1)( 1)( 2) ) ) +    (  6, tvrx2_tda18272_cal_map_t( list_of(389120000)(393216000)(397312000)(401408000), list_of(-2)( 0)(-1)( 1) ) ) +    (  7, tvrx2_tda18272_cal_map_t( list_of(455680000)(460800000)(465920000)(471040000), list_of( 0)(-2)(-3)( 1) ) ) +    (  8, tvrx2_tda18272_cal_map_t( list_of(555008000)(563200000)(570368000)(577536000), list_of(-1)( 0)(-3)(-2) ) ) +    (  9, tvrx2_tda18272_cal_map_t( list_of(647168000)(652288000)(658432000)(662528000), list_of(-6)(-3)( 0)(-5) ) ) +    ( 10, tvrx2_tda18272_cal_map_t( list_of(748544000)(755712000)(762880000)(770048000), list_of(-6)(-3)( 0)(-5) ) ) +    ( 11, tvrx2_tda18272_cal_map_t( list_of(792576000)(801792000)(809984000)(818176000), list_of(-5)(-2)( 0)(-4) ) ) +; + +static const std::vector<tvrx2_tda18272_freq_map_t> tvrx2_tda18272_freq_map = list_of +    ( tvrx2_tda18272_freq_map_t( 39936000, 0xFF, 0x17, 0) ) +    ( tvrx2_tda18272_freq_map_t( 40960000, 0xFD, 0x17, 0) ) +    ( tvrx2_tda18272_freq_map_t( 41984000, 0xF1, 0x15, 0) ) +    ( tvrx2_tda18272_freq_map_t( 43008000, 0xE5, 0x13, 0) ) +    ( tvrx2_tda18272_freq_map_t( 44032000, 0xDB, 0x13, 0) ) +    ( tvrx2_tda18272_freq_map_t( 45056000, 0xD1, 0x12, 0) ) +    ( tvrx2_tda18272_freq_map_t( 46080000, 0xC7, 0x10, 0) ) +    ( tvrx2_tda18272_freq_map_t( 47104000, 0xBE, 0x0F, 0) ) +    ( tvrx2_tda18272_freq_map_t( 48128000, 0xB5, 0x0F, 0) ) +    ( tvrx2_tda18272_freq_map_t( 49152000, 0xAD, 0x0F, 0) ) +    ( tvrx2_tda18272_freq_map_t( 50176000, 0xA6, 0x0F, 0) ) +    ( tvrx2_tda18272_freq_map_t( 51200000, 0x9F, 0x0F, 0) ) +    ( tvrx2_tda18272_freq_map_t( 52224000, 0x98, 0x0F, 0) ) +    ( tvrx2_tda18272_freq_map_t( 53248000, 0x91, 0x0F, 0) ) +    ( tvrx2_tda18272_freq_map_t( 54272000, 0x8B, 0x0F, 0) ) +    ( tvrx2_tda18272_freq_map_t( 55296000, 0x86, 0x0F, 0) ) +    ( tvrx2_tda18272_freq_map_t( 56320000, 0x80, 0x0F, 0) ) +    ( tvrx2_tda18272_freq_map_t( 57344000, 0x7B, 0x0E, 0) ) +    ( tvrx2_tda18272_freq_map_t( 58368000, 0x76, 0x0E, 0) ) +    ( tvrx2_tda18272_freq_map_t( 59392000, 0x72, 0x0D, 0) ) +    ( tvrx2_tda18272_freq_map_t( 60416000, 0x6D, 0x0D, 0) ) +    ( tvrx2_tda18272_freq_map_t( 61440000, 0x69, 0x0C, 0) ) +    ( tvrx2_tda18272_freq_map_t( 62464000, 0x65, 0x0C, 0) ) +    ( tvrx2_tda18272_freq_map_t( 63488000, 0x61, 0x0B, 0) ) +    ( tvrx2_tda18272_freq_map_t( 64512000, 0x5E, 0x0B, 0) ) +    ( tvrx2_tda18272_freq_map_t( 64512000, 0x5A, 0x0B, 0) ) +    ( tvrx2_tda18272_freq_map_t( 65536000, 0x57, 0x0A, 0) ) +    ( tvrx2_tda18272_freq_map_t( 66560000, 0x54, 0x0A, 0) ) +    ( tvrx2_tda18272_freq_map_t( 67584000, 0x51, 0x09, 0) ) +    ( tvrx2_tda18272_freq_map_t( 68608000, 0x4E, 0x09, 0) ) +    ( tvrx2_tda18272_freq_map_t( 69632000, 0x4B, 0x09, 0) ) +    ( tvrx2_tda18272_freq_map_t( 70656000, 0x49, 0x08, 0) ) +    ( tvrx2_tda18272_freq_map_t( 71680000, 0x46, 0x08, 0) ) +    ( tvrx2_tda18272_freq_map_t( 72704000, 0x44, 0x08, 0) ) +    ( tvrx2_tda18272_freq_map_t( 73728000, 0x41, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 74752000, 0x3F, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 75776000, 0x3D, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 76800000, 0x3B, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 77824000, 0x39, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 78848000, 0x37, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 79872000, 0x35, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 80896000, 0x33, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 81920000, 0x32, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 82944000, 0x30, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 83968000, 0x2F, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 84992000, 0x2D, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 86016000, 0x2C, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 87040000, 0x2A, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t( 88064000, 0x29, 0x06, 0) ) +    ( tvrx2_tda18272_freq_map_t( 89088000, 0x27, 0x06, 0) ) +    ( tvrx2_tda18272_freq_map_t( 90112000, 0x26, 0x06, 0) ) +    ( tvrx2_tda18272_freq_map_t( 91136000, 0x25, 0x06, 0) ) +    ( tvrx2_tda18272_freq_map_t( 92160000, 0x24, 0x06, 0) ) +    ( tvrx2_tda18272_freq_map_t( 93184000, 0x22, 0x05, 0) ) +    ( tvrx2_tda18272_freq_map_t( 94208000, 0x21, 0x05, 0) ) +    ( tvrx2_tda18272_freq_map_t( 95232000, 0x20, 0x05, 0) ) +    ( tvrx2_tda18272_freq_map_t( 96256000, 0x1F, 0x05, 0) ) +    ( tvrx2_tda18272_freq_map_t( 97280000, 0x1E, 0x05, 0) ) +    ( tvrx2_tda18272_freq_map_t( 98304000, 0x1D, 0x05, 0) ) +    ( tvrx2_tda18272_freq_map_t( 99328000, 0x1C, 0x04, 0) ) +    ( tvrx2_tda18272_freq_map_t(100352000, 0x1B, 0x04, 0) ) +    ( tvrx2_tda18272_freq_map_t(101376000, 0x1A, 0x04, 0) ) +    ( tvrx2_tda18272_freq_map_t(103424000, 0x19, 0x04, 0) ) +    ( tvrx2_tda18272_freq_map_t(104448000, 0x18, 0x04, 0) ) +    ( tvrx2_tda18272_freq_map_t(105472000, 0x17, 0x04, 0) ) +    ( tvrx2_tda18272_freq_map_t(106496000, 0x16, 0x03, 0) ) +    ( tvrx2_tda18272_freq_map_t(106496000, 0x15, 0x03, 0) ) +    ( tvrx2_tda18272_freq_map_t(108544000, 0x14, 0x03, 0) ) +    ( tvrx2_tda18272_freq_map_t(109568000, 0x13, 0x03, 0) ) +    ( tvrx2_tda18272_freq_map_t(111616000, 0x12, 0x03, 0) ) +    ( tvrx2_tda18272_freq_map_t(112640000, 0x11, 0x03, 0) ) +    ( tvrx2_tda18272_freq_map_t(113664000, 0x11, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t(114688000, 0x10, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t(115712000, 0x0F, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t(117760000, 0x0E, 0x07, 0) ) +    ( tvrx2_tda18272_freq_map_t(119808000, 0x0D, 0x06, 0) ) +    ( tvrx2_tda18272_freq_map_t(121856000, 0x0C, 0x06, 0) ) +    ( tvrx2_tda18272_freq_map_t(123904000, 0x0B, 0x06, 0) ) +    ( tvrx2_tda18272_freq_map_t(125952000, 0x0A, 0x05, 0) ) +    ( tvrx2_tda18272_freq_map_t(128000000, 0x09, 0x05, 0) ) +    ( tvrx2_tda18272_freq_map_t(130048000, 0x08, 0x05, 0) ) +    ( tvrx2_tda18272_freq_map_t(133120000, 0x07, 0x04, 0) ) +    ( tvrx2_tda18272_freq_map_t(135168000, 0x06, 0x04, 0) ) +    ( tvrx2_tda18272_freq_map_t(138240000, 0x05, 0x04, 0) ) +    ( tvrx2_tda18272_freq_map_t(141312000, 0x04, 0x04, 0) ) +    ( tvrx2_tda18272_freq_map_t(144384000, 0x03, 0x03, 0) ) +    ( tvrx2_tda18272_freq_map_t(145408000, 0xE0, 0x3F, 1) ) +    ( tvrx2_tda18272_freq_map_t(147456000, 0xDC, 0x37, 1) ) +    ( tvrx2_tda18272_freq_map_t(148480000, 0xD9, 0x32, 1) ) +    ( tvrx2_tda18272_freq_map_t(149504000, 0xD6, 0x2F, 1) ) +    ( tvrx2_tda18272_freq_map_t(149504000, 0xD2, 0x2F, 1) ) +    ( tvrx2_tda18272_freq_map_t(150528000, 0xCF, 0x2F, 1) ) +    ( tvrx2_tda18272_freq_map_t(151552000, 0xCC, 0x2B, 1) ) +    ( tvrx2_tda18272_freq_map_t(152576000, 0xC9, 0x27, 1) ) +    ( tvrx2_tda18272_freq_map_t(153600000, 0xC5, 0x27, 1) ) +    ( tvrx2_tda18272_freq_map_t(154624000, 0xC2, 0x25, 1) ) +    ( tvrx2_tda18272_freq_map_t(155648000, 0xBF, 0x23, 1) ) +    ( tvrx2_tda18272_freq_map_t(156672000, 0xBD, 0x20, 1) ) +    ( tvrx2_tda18272_freq_map_t(157696000, 0xBA, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(158720000, 0xB7, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(159744000, 0xB4, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(160768000, 0xB1, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(161792000, 0xAF, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(162816000, 0xAC, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(163840000, 0xAA, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(164864000, 0xA7, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(165888000, 0xA5, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(166912000, 0xA2, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(167936000, 0xA0, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(168960000, 0x9D, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(169984000, 0x9B, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(171008000, 0x99, 0x1F, 1) ) +    ( tvrx2_tda18272_freq_map_t(172032000, 0x97, 0x1E, 1) ) +    ( tvrx2_tda18272_freq_map_t(173056000, 0x95, 0x1D, 1) ) +    ( tvrx2_tda18272_freq_map_t(174080000, 0x92, 0x1C, 1) ) +    ( tvrx2_tda18272_freq_map_t(175104000, 0x90, 0x1B, 1) ) +    ( tvrx2_tda18272_freq_map_t(176128000, 0x8E, 0x1A, 1) ) +    ( tvrx2_tda18272_freq_map_t(177152000, 0x8C, 0x19, 1) ) +    ( tvrx2_tda18272_freq_map_t(178176000, 0x8A, 0x18, 1) ) +    ( tvrx2_tda18272_freq_map_t(179200000, 0x88, 0x17, 1) ) +    ( tvrx2_tda18272_freq_map_t(180224000, 0x86, 0x17, 1) ) +    ( tvrx2_tda18272_freq_map_t(181248000, 0x84, 0x17, 1) ) +    ( tvrx2_tda18272_freq_map_t(182272000, 0x82, 0x17, 1) ) +    ( tvrx2_tda18272_freq_map_t(183296000, 0x81, 0x17, 1) ) +    ( tvrx2_tda18272_freq_map_t(184320000, 0x7F, 0x17, 1) ) +    ( tvrx2_tda18272_freq_map_t(185344000, 0x7D, 0x16, 1) ) +    ( tvrx2_tda18272_freq_map_t(186368000, 0x7B, 0x15, 1) ) +    ( tvrx2_tda18272_freq_map_t(187392000, 0x7A, 0x14, 1) ) +    ( tvrx2_tda18272_freq_map_t(188416000, 0x78, 0x14, 1) ) +    ( tvrx2_tda18272_freq_map_t(189440000, 0x76, 0x13, 1) ) +    ( tvrx2_tda18272_freq_map_t(190464000, 0x75, 0x13, 1) ) +    ( tvrx2_tda18272_freq_map_t(191488000, 0x73, 0x13, 1) ) +    ( tvrx2_tda18272_freq_map_t(192512000, 0x71, 0x12, 1) ) +    ( tvrx2_tda18272_freq_map_t(192512000, 0x70, 0x11, 1) ) +    ( tvrx2_tda18272_freq_map_t(193536000, 0x6E, 0x11, 1) ) +    ( tvrx2_tda18272_freq_map_t(194560000, 0x6D, 0x10, 1) ) +    ( tvrx2_tda18272_freq_map_t(195584000, 0x6B, 0x10, 1) ) +    ( tvrx2_tda18272_freq_map_t(196608000, 0x6A, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(197632000, 0x68, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(198656000, 0x67, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(199680000, 0x65, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(200704000, 0x64, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(201728000, 0x63, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(202752000, 0x61, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(203776000, 0x60, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(204800000, 0x5F, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(205824000, 0x5D, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(206848000, 0x5C, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(207872000, 0x5B, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(208896000, 0x5A, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(209920000, 0x58, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(210944000, 0x57, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(211968000, 0x56, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(212992000, 0x55, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(214016000, 0x54, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(215040000, 0x53, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(216064000, 0x52, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(217088000, 0x50, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(218112000, 0x4F, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(219136000, 0x4E, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(220160000, 0x4D, 0x0E, 1) ) +    ( tvrx2_tda18272_freq_map_t(221184000, 0x4C, 0x0E, 1) ) +    ( tvrx2_tda18272_freq_map_t(222208000, 0x4B, 0x0E, 1) ) +    ( tvrx2_tda18272_freq_map_t(223232000, 0x4A, 0x0E, 1) ) +    ( tvrx2_tda18272_freq_map_t(224256000, 0x49, 0x0D, 1) ) +    ( tvrx2_tda18272_freq_map_t(225280000, 0x48, 0x0D, 1) ) +    ( tvrx2_tda18272_freq_map_t(226304000, 0x47, 0x0D, 1) ) +    ( tvrx2_tda18272_freq_map_t(227328000, 0x46, 0x0D, 1) ) +    ( tvrx2_tda18272_freq_map_t(228352000, 0x45, 0x0C, 1) ) +    ( tvrx2_tda18272_freq_map_t(229376000, 0x44, 0x0C, 1) ) +    ( tvrx2_tda18272_freq_map_t(230400000, 0x43, 0x0C, 1) ) +    ( tvrx2_tda18272_freq_map_t(231424000, 0x42, 0x0C, 1) ) +    ( tvrx2_tda18272_freq_map_t(232448000, 0x42, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(233472000, 0x41, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(234496000, 0x40, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(234496000, 0x3F, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(235520000, 0x3E, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(236544000, 0x3D, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(237568000, 0x3C, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(239616000, 0x3B, 0x0A, 1) ) +    ( tvrx2_tda18272_freq_map_t(240640000, 0x3A, 0x0A, 1) ) +    ( tvrx2_tda18272_freq_map_t(241664000, 0x39, 0x0A, 1) ) +    ( tvrx2_tda18272_freq_map_t(242688000, 0x38, 0x0A, 1) ) +    ( tvrx2_tda18272_freq_map_t(244736000, 0x37, 0x09, 1) ) +    ( tvrx2_tda18272_freq_map_t(245760000, 0x36, 0x09, 1) ) +    ( tvrx2_tda18272_freq_map_t(246784000, 0x35, 0x09, 1) ) +    ( tvrx2_tda18272_freq_map_t(248832000, 0x34, 0x09, 1) ) +    ( tvrx2_tda18272_freq_map_t(249856000, 0x33, 0x09, 1) ) +    ( tvrx2_tda18272_freq_map_t(250880000, 0x32, 0x08, 1) ) +    ( tvrx2_tda18272_freq_map_t(252928000, 0x31, 0x08, 1) ) +    ( tvrx2_tda18272_freq_map_t(253952000, 0x30, 0x08, 1) ) +    ( tvrx2_tda18272_freq_map_t(256000000, 0x2F, 0x08, 1) ) +    ( tvrx2_tda18272_freq_map_t(257024000, 0x2E, 0x08, 1) ) +    ( tvrx2_tda18272_freq_map_t(259072000, 0x2D, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(260096000, 0x2C, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(262144000, 0x2B, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(264192000, 0x2A, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(265216000, 0x29, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(267264000, 0x28, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(269312000, 0x27, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(270336000, 0x26, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(272384000, 0x25, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(274432000, 0x24, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(276480000, 0x23, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(277504000, 0x22, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(279552000, 0x21, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(281600000, 0x20, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(283648000, 0x1F, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(285696000, 0x1E, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(287744000, 0x1D, 0x0F, 1) ) +    ( tvrx2_tda18272_freq_map_t(289792000, 0x1C, 0x0E, 1) ) +    ( tvrx2_tda18272_freq_map_t(291840000, 0x1B, 0x0E, 1) ) +    ( tvrx2_tda18272_freq_map_t(293888000, 0x1A, 0x0D, 1) ) +    ( tvrx2_tda18272_freq_map_t(296960000, 0x19, 0x0D, 1) ) +    ( tvrx2_tda18272_freq_map_t(299008000, 0x18, 0x0C, 1) ) +    ( tvrx2_tda18272_freq_map_t(301056000, 0x17, 0x0C, 1) ) +    ( tvrx2_tda18272_freq_map_t(304128000, 0x16, 0x0C, 1) ) +    ( tvrx2_tda18272_freq_map_t(306176000, 0x15, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(309248000, 0x14, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(312320000, 0x13, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(314368000, 0x12, 0x0B, 1) ) +    ( tvrx2_tda18272_freq_map_t(317440000, 0x11, 0x0A, 1) ) +    ( tvrx2_tda18272_freq_map_t(320512000, 0x10, 0x0A, 1) ) +    ( tvrx2_tda18272_freq_map_t(322560000, 0x0F, 0x0A, 1) ) +    ( tvrx2_tda18272_freq_map_t(325632000, 0x0E, 0x09, 1) ) +    ( tvrx2_tda18272_freq_map_t(328704000, 0x0D, 0x09, 1) ) +    ( tvrx2_tda18272_freq_map_t(331776000, 0x0C, 0x08, 1) ) +    ( tvrx2_tda18272_freq_map_t(335872000, 0x0B, 0x08, 1) ) +    ( tvrx2_tda18272_freq_map_t(338944000, 0x0A, 0x08, 1) ) +    ( tvrx2_tda18272_freq_map_t(343040000, 0x09, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(346112000, 0x08, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(350208000, 0x07, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(354304000, 0x06, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(358400000, 0x05, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(362496000, 0x04, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(365568000, 0x04, 0x07, 1) ) +    ( tvrx2_tda18272_freq_map_t(367616000, 0xDA, 0x2A, 2) ) +    ( tvrx2_tda18272_freq_map_t(367616000, 0xD9, 0x27, 2) ) +    ( tvrx2_tda18272_freq_map_t(368640000, 0xD8, 0x27, 2) ) +    ( tvrx2_tda18272_freq_map_t(369664000, 0xD6, 0x27, 2) ) +    ( tvrx2_tda18272_freq_map_t(370688000, 0xD5, 0x27, 2) ) +    ( tvrx2_tda18272_freq_map_t(371712000, 0xD3, 0x25, 2) ) +    ( tvrx2_tda18272_freq_map_t(372736000, 0xD2, 0x23, 2) ) +    ( tvrx2_tda18272_freq_map_t(373760000, 0xD0, 0x23, 2) ) +    ( tvrx2_tda18272_freq_map_t(374784000, 0xCF, 0x21, 2) ) +    ( tvrx2_tda18272_freq_map_t(375808000, 0xCD, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(376832000, 0xCC, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(377856000, 0xCA, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(378880000, 0xC9, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(379904000, 0xC7, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(380928000, 0xC6, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(381952000, 0xC4, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(382976000, 0xC3, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(384000000, 0xC1, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(385024000, 0xC0, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(386048000, 0xBF, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(387072000, 0xBD, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(388096000, 0xBC, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(389120000, 0xBB, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(390144000, 0xB9, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(391168000, 0xB8, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(392192000, 0xB7, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(393216000, 0xB5, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(394240000, 0xB4, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(395264000, 0xB3, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(396288000, 0xB1, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(397312000, 0xB0, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(398336000, 0xAF, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(399360000, 0xAD, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(400384000, 0xAC, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(401408000, 0xAB, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(402432000, 0xAA, 0x1F, 2) ) +    ( tvrx2_tda18272_freq_map_t(403456000, 0xA8, 0x1E, 2) ) +    ( tvrx2_tda18272_freq_map_t(404480000, 0xA7, 0x1D, 2) ) +    ( tvrx2_tda18272_freq_map_t(405504000, 0xA6, 0x1D, 2) ) +    ( tvrx2_tda18272_freq_map_t(405504000, 0xA5, 0x1C, 2) ) +    ( tvrx2_tda18272_freq_map_t(406528000, 0xA3, 0x1C, 2) ) +    ( tvrx2_tda18272_freq_map_t(407552000, 0xA2, 0x1B, 2) ) +    ( tvrx2_tda18272_freq_map_t(408576000, 0xA1, 0x1B, 2) ) +    ( tvrx2_tda18272_freq_map_t(409600000, 0xA0, 0x1B, 2) ) +    ( tvrx2_tda18272_freq_map_t(410624000, 0x9F, 0x1A, 2) ) +    ( tvrx2_tda18272_freq_map_t(411648000, 0x9D, 0x1A, 2) ) +    ( tvrx2_tda18272_freq_map_t(412672000, 0x9C, 0x19, 2) ) +    ( tvrx2_tda18272_freq_map_t(413696000, 0x9B, 0x18, 2) ) +    ( tvrx2_tda18272_freq_map_t(414720000, 0x9A, 0x18, 2) ) +    ( tvrx2_tda18272_freq_map_t(415744000, 0x99, 0x17, 2) ) +    ( tvrx2_tda18272_freq_map_t(416768000, 0x98, 0x17, 2) ) +    ( tvrx2_tda18272_freq_map_t(417792000, 0x97, 0x17, 2) ) +    ( tvrx2_tda18272_freq_map_t(418816000, 0x95, 0x17, 2) ) +    ( tvrx2_tda18272_freq_map_t(419840000, 0x94, 0x17, 2) ) +    ( tvrx2_tda18272_freq_map_t(420864000, 0x93, 0x17, 2) ) +    ( tvrx2_tda18272_freq_map_t(421888000, 0x92, 0x17, 2) ) +    ( tvrx2_tda18272_freq_map_t(422912000, 0x91, 0x17, 2) ) +    ( tvrx2_tda18272_freq_map_t(423936000, 0x90, 0x17, 2) ) +    ( tvrx2_tda18272_freq_map_t(424960000, 0x8F, 0x17, 2) ) +    ( tvrx2_tda18272_freq_map_t(425984000, 0x8E, 0x16, 2) ) +    ( tvrx2_tda18272_freq_map_t(427008000, 0x8D, 0x16, 2) ) +    ( tvrx2_tda18272_freq_map_t(428032000, 0x8C, 0x15, 2) ) +    ( tvrx2_tda18272_freq_map_t(429056000, 0x8B, 0x15, 2) ) +    ( tvrx2_tda18272_freq_map_t(430080000, 0x8A, 0x15, 2) ) +    ( tvrx2_tda18272_freq_map_t(431104000, 0x88, 0x14, 2) ) +    ( tvrx2_tda18272_freq_map_t(432128000, 0x87, 0x14, 2) ) +    ( tvrx2_tda18272_freq_map_t(433152000, 0x86, 0x14, 2) ) +    ( tvrx2_tda18272_freq_map_t(434176000, 0x85, 0x13, 2) ) +    ( tvrx2_tda18272_freq_map_t(435200000, 0x84, 0x13, 2) ) +    ( tvrx2_tda18272_freq_map_t(436224000, 0x83, 0x13, 2) ) +    ( tvrx2_tda18272_freq_map_t(437248000, 0x82, 0x13, 2) ) +    ( tvrx2_tda18272_freq_map_t(438272000, 0x81, 0x13, 2) ) +    ( tvrx2_tda18272_freq_map_t(439296000, 0x80, 0x12, 2) ) +    ( tvrx2_tda18272_freq_map_t(440320000, 0x7F, 0x12, 2) ) +    ( tvrx2_tda18272_freq_map_t(441344000, 0x7E, 0x12, 2) ) +    ( tvrx2_tda18272_freq_map_t(442368000, 0x7D, 0x11, 2) ) +    ( tvrx2_tda18272_freq_map_t(444416000, 0x7C, 0x11, 2) ) +    ( tvrx2_tda18272_freq_map_t(445440000, 0x7B, 0x10, 2) ) +    ( tvrx2_tda18272_freq_map_t(446464000, 0x7A, 0x10, 2) ) +    ( tvrx2_tda18272_freq_map_t(447488000, 0x79, 0x10, 2) ) +    ( tvrx2_tda18272_freq_map_t(448512000, 0x78, 0x10, 2) ) +    ( tvrx2_tda18272_freq_map_t(448512000, 0x77, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(449536000, 0x76, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(450560000, 0x75, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(451584000, 0x74, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(452608000, 0x73, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(453632000, 0x72, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(454656000, 0x71, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(455680000, 0x70, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(457728000, 0x6F, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(458752000, 0x6E, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(459776000, 0x6D, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(460800000, 0x6C, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(461824000, 0x6B, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(462848000, 0x6A, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(464896000, 0x69, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(465920000, 0x68, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(466944000, 0x67, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(467968000, 0x66, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(468992000, 0x65, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(471040000, 0x64, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(472064000, 0x63, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(473088000, 0x62, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(474112000, 0x61, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(476160000, 0x60, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(477184000, 0x5F, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(478208000, 0x5E, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(479232000, 0x5D, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(481280000, 0x5C, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(482304000, 0x5B, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(483328000, 0x5A, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(485376000, 0x59, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(486400000, 0x58, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(487424000, 0x57, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(489472000, 0x56, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(490496000, 0x55, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(490496000, 0x54, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(492544000, 0x53, 0x0E, 2) ) +    ( tvrx2_tda18272_freq_map_t(493568000, 0x52, 0x0E, 2) ) +    ( tvrx2_tda18272_freq_map_t(495616000, 0x51, 0x0E, 2) ) +    ( tvrx2_tda18272_freq_map_t(496640000, 0x50, 0x0E, 2) ) +    ( tvrx2_tda18272_freq_map_t(497664000, 0x4F, 0x0E, 2) ) +    ( tvrx2_tda18272_freq_map_t(499712000, 0x4E, 0x0D, 2) ) +    ( tvrx2_tda18272_freq_map_t(500736000, 0x4D, 0x0D, 2) ) +    ( tvrx2_tda18272_freq_map_t(502784000, 0x4C, 0x0D, 2) ) +    ( tvrx2_tda18272_freq_map_t(503808000, 0x4B, 0x0D, 2) ) +    ( tvrx2_tda18272_freq_map_t(505856000, 0x4A, 0x0C, 2) ) +    ( tvrx2_tda18272_freq_map_t(506880000, 0x49, 0x0C, 2) ) +    ( tvrx2_tda18272_freq_map_t(508928000, 0x48, 0x0C, 2) ) +    ( tvrx2_tda18272_freq_map_t(509952000, 0x47, 0x0C, 2) ) +    ( tvrx2_tda18272_freq_map_t(512000000, 0x46, 0x0C, 2) ) +    ( tvrx2_tda18272_freq_map_t(513024000, 0x45, 0x0B, 2) ) +    ( tvrx2_tda18272_freq_map_t(515072000, 0x44, 0x0B, 2) ) +    ( tvrx2_tda18272_freq_map_t(517120000, 0x43, 0x0B, 2) ) +    ( tvrx2_tda18272_freq_map_t(518144000, 0x42, 0x0B, 2) ) +    ( tvrx2_tda18272_freq_map_t(520192000, 0x41, 0x0B, 2) ) +    ( tvrx2_tda18272_freq_map_t(521216000, 0x40, 0x0B, 2) ) +    ( tvrx2_tda18272_freq_map_t(523264000, 0x3F, 0x0B, 2) ) +    ( tvrx2_tda18272_freq_map_t(525312000, 0x3E, 0x0B, 2) ) +    ( tvrx2_tda18272_freq_map_t(526336000, 0x3D, 0x0B, 2) ) +    ( tvrx2_tda18272_freq_map_t(528384000, 0x3C, 0x0A, 2) ) +    ( tvrx2_tda18272_freq_map_t(530432000, 0x3B, 0x0A, 2) ) +    ( tvrx2_tda18272_freq_map_t(531456000, 0x3A, 0x0A, 2) ) +    ( tvrx2_tda18272_freq_map_t(533504000, 0x39, 0x0A, 2) ) +    ( tvrx2_tda18272_freq_map_t(534528000, 0x38, 0x0A, 2) ) +    ( tvrx2_tda18272_freq_map_t(536576000, 0x37, 0x0A, 2) ) +    ( tvrx2_tda18272_freq_map_t(537600000, 0x36, 0x09, 2) ) +    ( tvrx2_tda18272_freq_map_t(539648000, 0x35, 0x09, 2) ) +    ( tvrx2_tda18272_freq_map_t(541696000, 0x34, 0x09, 2) ) +    ( tvrx2_tda18272_freq_map_t(543744000, 0x33, 0x09, 2) ) +    ( tvrx2_tda18272_freq_map_t(544768000, 0x32, 0x09, 2) ) +    ( tvrx2_tda18272_freq_map_t(546816000, 0x31, 0x09, 2) ) +    ( tvrx2_tda18272_freq_map_t(548864000, 0x30, 0x08, 2) ) +    ( tvrx2_tda18272_freq_map_t(550912000, 0x2F, 0x08, 2) ) +    ( tvrx2_tda18272_freq_map_t(552960000, 0x2E, 0x08, 2) ) +    ( tvrx2_tda18272_freq_map_t(555008000, 0x2D, 0x08, 2) ) +    ( tvrx2_tda18272_freq_map_t(557056000, 0x2C, 0x08, 2) ) +    ( tvrx2_tda18272_freq_map_t(559104000, 0x2B, 0x08, 2) ) +    ( tvrx2_tda18272_freq_map_t(561152000, 0x2A, 0x07, 2) ) +    ( tvrx2_tda18272_freq_map_t(563200000, 0x29, 0x07, 2) ) +    ( tvrx2_tda18272_freq_map_t(565248000, 0x28, 0x07, 2) ) +    ( tvrx2_tda18272_freq_map_t(567296000, 0x27, 0x07, 2) ) +    ( tvrx2_tda18272_freq_map_t(569344000, 0x26, 0x07, 2) ) +    ( tvrx2_tda18272_freq_map_t(570368000, 0x26, 0x07, 2) ) +    ( tvrx2_tda18272_freq_map_t(571392000, 0x25, 0x07, 2) ) +    ( tvrx2_tda18272_freq_map_t(573440000, 0x24, 0x07, 2) ) +    ( tvrx2_tda18272_freq_map_t(575488000, 0x23, 0x07, 2) ) +    ( tvrx2_tda18272_freq_map_t(577536000, 0x22, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(578560000, 0x21, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(580608000, 0x20, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(583680000, 0x1F, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(585728000, 0x1E, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(587776000, 0x1D, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(589824000, 0x1C, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(592896000, 0x1B, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(594944000, 0x1A, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(596992000, 0x19, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(600064000, 0x18, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(602112000, 0x17, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(604160000, 0x16, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(607232000, 0x15, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(609280000, 0x14, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(612352000, 0x13, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(615424000, 0x12, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(617472000, 0x11, 0x0F, 2) ) +    ( tvrx2_tda18272_freq_map_t(619520000, 0x10, 0x0E, 2) ) +    ( tvrx2_tda18272_freq_map_t(621568000, 0x0F, 0x0E, 2) ) +    ( tvrx2_tda18272_freq_map_t(623616000, 0x0F, 0x0E, 2) ) +    ( tvrx2_tda18272_freq_map_t(624640000, 0xA3, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(625664000, 0xA2, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(626688000, 0xA1, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(627712000, 0xA0, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(628736000, 0x9F, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(630784000, 0x9E, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(631808000, 0x9D, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(632832000, 0x9C, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(633856000, 0x9B, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(635904000, 0x9A, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(636928000, 0x99, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(637952000, 0x98, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(638976000, 0x97, 0x1F, 3) ) +    ( tvrx2_tda18272_freq_map_t(641024000, 0x96, 0x1E, 3) ) +    ( tvrx2_tda18272_freq_map_t(642048000, 0x95, 0x1E, 3) ) +    ( tvrx2_tda18272_freq_map_t(643072000, 0x94, 0x1E, 3) ) +    ( tvrx2_tda18272_freq_map_t(644096000, 0x93, 0x1D, 3) ) +    ( tvrx2_tda18272_freq_map_t(646144000, 0x92, 0x1D, 3) ) +    ( tvrx2_tda18272_freq_map_t(647168000, 0x91, 0x1C, 3) ) +    ( tvrx2_tda18272_freq_map_t(648192000, 0x90, 0x1C, 3) ) +    ( tvrx2_tda18272_freq_map_t(650240000, 0x8F, 0x1B, 3) ) +    ( tvrx2_tda18272_freq_map_t(651264000, 0x8E, 0x1B, 3) ) +    ( tvrx2_tda18272_freq_map_t(652288000, 0x8D, 0x1B, 3) ) +    ( tvrx2_tda18272_freq_map_t(654336000, 0x8C, 0x1B, 3) ) +    ( tvrx2_tda18272_freq_map_t(655360000, 0x8B, 0x1B, 3) ) +    ( tvrx2_tda18272_freq_map_t(656384000, 0x8A, 0x1B, 3) ) +    ( tvrx2_tda18272_freq_map_t(658432000, 0x89, 0x1A, 3) ) +    ( tvrx2_tda18272_freq_map_t(659456000, 0x88, 0x1A, 3) ) +    ( tvrx2_tda18272_freq_map_t(660480000, 0x87, 0x1A, 3) ) +    ( tvrx2_tda18272_freq_map_t(661504000, 0x86, 0x19, 3) ) +    ( tvrx2_tda18272_freq_map_t(662528000, 0x85, 0x19, 3) ) +    ( tvrx2_tda18272_freq_map_t(664576000, 0x84, 0x18, 3) ) +    ( tvrx2_tda18272_freq_map_t(665600000, 0x83, 0x18, 3) ) +    ( tvrx2_tda18272_freq_map_t(666624000, 0x82, 0x18, 3) ) +    ( tvrx2_tda18272_freq_map_t(668672000, 0x81, 0x18, 3) ) +    ( tvrx2_tda18272_freq_map_t(669696000, 0x80, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(671744000, 0x7F, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(672768000, 0x7E, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(674816000, 0x7D, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(675840000, 0x7C, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(676864000, 0x7B, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(678912000, 0x7A, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(679936000, 0x79, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(681984000, 0x78, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(683008000, 0x77, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(685056000, 0x76, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(686080000, 0x75, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(688128000, 0x74, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(689152000, 0x73, 0x17, 3) ) +    ( tvrx2_tda18272_freq_map_t(691200000, 0x72, 0x16, 3) ) +    ( tvrx2_tda18272_freq_map_t(693248000, 0x71, 0x16, 3) ) +    ( tvrx2_tda18272_freq_map_t(694272000, 0x70, 0x16, 3) ) +    ( tvrx2_tda18272_freq_map_t(696320000, 0x6F, 0x15, 3) ) +    ( tvrx2_tda18272_freq_map_t(697344000, 0x6E, 0x15, 3) ) +    ( tvrx2_tda18272_freq_map_t(699392000, 0x6D, 0x15, 3) ) +    ( tvrx2_tda18272_freq_map_t(700416000, 0x6C, 0x15, 3) ) +    ( tvrx2_tda18272_freq_map_t(702464000, 0x6B, 0x14, 3) ) +    ( tvrx2_tda18272_freq_map_t(704512000, 0x6A, 0x14, 3) ) +    ( tvrx2_tda18272_freq_map_t(704512000, 0x69, 0x14, 3) ) +    ( tvrx2_tda18272_freq_map_t(706560000, 0x68, 0x14, 3) ) +    ( tvrx2_tda18272_freq_map_t(707584000, 0x67, 0x13, 3) ) +    ( tvrx2_tda18272_freq_map_t(709632000, 0x66, 0x13, 3) ) +    ( tvrx2_tda18272_freq_map_t(711680000, 0x65, 0x13, 3) ) +    ( tvrx2_tda18272_freq_map_t(712704000, 0x64, 0x13, 3) ) +    ( tvrx2_tda18272_freq_map_t(714752000, 0x63, 0x13, 3) ) +    ( tvrx2_tda18272_freq_map_t(716800000, 0x62, 0x13, 3) ) +    ( tvrx2_tda18272_freq_map_t(717824000, 0x61, 0x13, 3) ) +    ( tvrx2_tda18272_freq_map_t(719872000, 0x60, 0x13, 3) ) +    ( tvrx2_tda18272_freq_map_t(721920000, 0x5F, 0x12, 3) ) +    ( tvrx2_tda18272_freq_map_t(723968000, 0x5E, 0x12, 3) ) +    ( tvrx2_tda18272_freq_map_t(724992000, 0x5D, 0x12, 3) ) +    ( tvrx2_tda18272_freq_map_t(727040000, 0x5C, 0x12, 3) ) +    ( tvrx2_tda18272_freq_map_t(729088000, 0x5B, 0x11, 3) ) +    ( tvrx2_tda18272_freq_map_t(731136000, 0x5A, 0x11, 3) ) +    ( tvrx2_tda18272_freq_map_t(732160000, 0x59, 0x11, 3) ) +    ( tvrx2_tda18272_freq_map_t(734208000, 0x58, 0x11, 3) ) +    ( tvrx2_tda18272_freq_map_t(736256000, 0x57, 0x10, 3) ) +    ( tvrx2_tda18272_freq_map_t(738304000, 0x56, 0x10, 3) ) +    ( tvrx2_tda18272_freq_map_t(740352000, 0x55, 0x10, 3) ) +    ( tvrx2_tda18272_freq_map_t(741376000, 0x54, 0x10, 3) ) +    ( tvrx2_tda18272_freq_map_t(743424000, 0x53, 0x10, 3) ) +    ( tvrx2_tda18272_freq_map_t(745472000, 0x52, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(746496000, 0x51, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(748544000, 0x50, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(750592000, 0x4F, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(752640000, 0x4E, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(753664000, 0x4D, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(755712000, 0x4C, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(757760000, 0x4B, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(759808000, 0x4A, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(761856000, 0x49, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(762880000, 0x49, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(763904000, 0x48, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(765952000, 0x47, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(768000000, 0x46, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(770048000, 0x45, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(772096000, 0x44, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(774144000, 0x43, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(776192000, 0x42, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(778240000, 0x41, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(780288000, 0x40, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(783360000, 0x3F, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(785408000, 0x3E, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(787456000, 0x3D, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(789504000, 0x3C, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(790528000, 0x3B, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(792576000, 0x3A, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(794624000, 0x39, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(797696000, 0x38, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(799744000, 0x37, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(801792000, 0x36, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(803840000, 0x35, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(806912000, 0x34, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(808960000, 0x33, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(809984000, 0x33, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(811008000, 0x32, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(813056000, 0x31, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(816128000, 0x30, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(818176000, 0x2F, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(820224000, 0x2E, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(823296000, 0x2D, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(825344000, 0x2C, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(828416000, 0x2B, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(830464000, 0x2A, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(832512000, 0x29, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(834560000, 0x28, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(836608000, 0x27, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(839680000, 0x26, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(841728000, 0x25, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(844800000, 0x24, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(847872000, 0x23, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(849920000, 0x22, 0x0F, 3) ) +    ( tvrx2_tda18272_freq_map_t(852992000, 0x21, 0x0E, 3) ) +    ( tvrx2_tda18272_freq_map_t(855040000, 0x20, 0x0E, 3) ) +    ( tvrx2_tda18272_freq_map_t(858112000, 0x1F, 0x0E, 3) ) +    ( tvrx2_tda18272_freq_map_t(861184000, 0x1E, 0x0E, 3) ) +    ( tvrx2_tda18272_freq_map_t(863232000, 0x1D, 0x0E, 3) ) +    ( tvrx2_tda18272_freq_map_t(866304000, 0x1C, 0x0E, 3) ) +    ( tvrx2_tda18272_freq_map_t(900096000, 0x10, 0x0C, 3) ) +    ( tvrx2_tda18272_freq_map_t(929792000, 0x07, 0x0B, 3) ) +    ( tvrx2_tda18272_freq_map_t(969728000, 0x00, 0x0A, 3) ) +; + +static const freq_range_t tvrx2_freq_range(42e6, 870e6); + +static const freq_range_t tvrx2_bandwidth_range = list_of +    (range_t(1.7e6)) +    (range_t(6.0e6)) +    (range_t(7.0e6)) +    (range_t(8.0e6)) +    (range_t(10.0e6)) +; + +static const uhd::dict<std::string, std::string> tvrx2_sd_name_to_antennas = map_list_of +    ("RX1", "J100") +    ("RX2", "J140") +; + +static const uhd::dict<std::string, std::string> tvrx2_sd_name_to_conn = map_list_of +    ("RX1",  "Q") +    ("RX2",  "I") +; + +static const uhd::dict<std::string, boost::uint8_t> tvrx2_sd_name_to_i2c_addr = map_list_of +    ("RX1", 0x63) +    ("RX2", 0x60) +; + +static const uhd::dict<std::string, boost::uint8_t> tvrx2_sd_name_to_irq_io = map_list_of +    ("RX1", (RX1_IRQ)) +    ("RX2", (RX2_IRQ)) +; + +static const uhd::dict<std::string, dboard_iface::aux_dac_t> tvrx2_sd_name_to_dac = map_list_of +    ("RX1", dboard_iface::AUX_DAC_A) +    ("RX2", dboard_iface::AUX_DAC_B) +; + +static const uhd::dict<std::string, gain_range_t> tvrx2_gain_ranges = map_list_of +//    ("LNA", gain_range_t(-12, 15, 3)) +//    ("RF_FILTER", gain_range_t(-11, -2, 3)) +//    ("IR_MIXER", gain_range_t(2, 14, 3)) +//    ("LPF", gain_range_t(0, 9, 3)) +    ("IF", gain_range_t(0, 30, 0.5)) +; + +/*********************************************************************** + * The TVRX2 dboard class + **********************************************************************/ +class tvrx2 : public rx_dboard_base{ +public: +    tvrx2(ctor_args_t args); +    ~tvrx2(void); + +private: +    double _freq_scalar; +    double _lo_freq; +    double _if_freq; +    double _bandwidth; +    uhd::dict<std::string, double> _gains; +    tda18272hnm_regs_t _tda18272hnm_regs; +    uhd::dict<boost::uint32_t, tvrx2_tda18272_rfcal_result_t> _rfcal_results; +    uhd::dict<boost::uint32_t, tvrx2_tda18272_rfcal_coeffs_t> _rfcal_coeffs; + +    bool _enabled; + +    bool set_enabled(bool); + +    double set_lo_freq(double target_freq); +    double set_gain(double gain, const std::string &name); +    double set_bandwidth(double bandwidth); + +    void set_scaled_rf_freq(double rf_freq); +    double get_scaled_rf_freq(void); +    void set_scaled_if_freq(double if_freq); +    double get_scaled_if_freq(void); +    void send_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg); +    void read_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg); + +    freq_range_t get_tda18272_rfcal_result_freq_range(boost::uint32_t result); +    void tvrx2_tda18272_init_rfcal(void); +    void tvrx2_tda18272_tune_rf_filter(boost::uint32_t uRF); +    void soft_calibration(void); +    void transition_0(void); +    void transition_1(void); +    void transition_2(int rf_freq); +    void transition_3(void); +    void transition_4(int rf_freq); +    void wait_irq(void); +    void test_rf_filter_robustness(void); + +/*********************************************************************** + * The TVRX2 class helper functions + **********************************************************************/ +    /*! +     * Is the IRQ set or cleared? +     * \return true for set +     */ +    bool get_irq(void){ +        read_reg(0x8, 0x8); + +        //return irq status +        bool irq = _tda18272hnm_regs.irq_status == tda18272hnm_regs_t::IRQ_STATUS_SET; + +        UHD_LOGV(often) << boost::format( +            "TVRX2 (%s): IRQ %d" +        ) % (get_subdev_name()) % irq << std::endl; + +        return irq; +    } + +    /*! +     * In Power-On Reset State? +     *      Check POR logic for reset state (causes POR to clear) +     * \return true for reset +     */ +    bool get_power_reset(void){ +        read_reg(0x5, 0x5); + +        //return POR state +        bool por = _tda18272hnm_regs.por == tda18272hnm_regs_t::POR_RESET; + +        UHD_LOGV(often) << boost::format( +            "TVRX2 (%s): POR %d" +        ) % (get_subdev_name()) % int(_tda18272hnm_regs.por) << std::endl; + +        return por; +    } + +    /*! +     * Get the lock detect status of the LO. +     * \return sensor for locked +     */ +    sensor_value_t get_locked(void){ +        read_reg(0x5, 0x5); + +        //return lock detect +        bool locked = _tda18272hnm_regs.lo_lock == tda18272hnm_regs_t::LO_LOCK_LOCKED; + +        UHD_LOGV(often) << boost::format( +            "TVRX2 (%s): locked %d" +        ) % (get_subdev_name()) % locked << std::endl; + +        return sensor_value_t("LO", locked, "locked", "unlocked"); +    } + +    /*! +     * Read the RSSI from the registers +     * Read the RSSI from the aux adc +     * \return the rssi sensor in dB(m?) FIXME +     */ +    sensor_value_t get_rssi(void){ +        //Launch RSSI calculation with MSM statemachine +        _tda18272hnm_regs.set_reg(0x19, 0x80); //set MSM_byte_1 for rssi calculation +        _tda18272hnm_regs.set_reg(0x1A, 0x01); //set MSM_byte_2 for launching rssi calculation + +        send_reg(0x19, 0x1A); + +        wait_irq(); + +        //read rssi in dBuV +        read_reg(0x7, 0x7); + +        //calculate the rssi from the voltage +        double rssi_dBuV = 40.0 + double(((110.0 - 40.0)/128.0) * _tda18272hnm_regs.get_reg(0x7)); +        double rssi =  rssi_dBuV - 107.0; //convert to dBm in 50ohm environment ( -108.8 if 75ohm ) FIXME + +        return sensor_value_t("RSSI", rssi, "dBm"); +    } + +    /*! +     * Read the Temperature from the registers +     * \return the temp in degC +     */ +    sensor_value_t get_temp(void){ +        //Enable Temperature reading +        _tda18272hnm_regs.tm_on = tda18272hnm_regs_t::TM_ON_SENSOR_ON; +        send_reg(0x4, 0x4); + +        //read temp in degC +        read_reg(0x3, 0x3); + +        UHD_LOGV(often) << boost::format( +            "TVRX2 (%s): Temperature %f C" +        ) % (get_subdev_name()) % (double(_tda18272hnm_regs.tm_d)) << std::endl; + +        //Disable Temperature reading +        _tda18272hnm_regs.tm_on = tda18272hnm_regs_t::TM_ON_SENSOR_OFF; +        send_reg(0x4, 0x4); + +        return sensor_value_t("TEMP", double(_tda18272hnm_regs.tm_d), "degC"); +    } +}; + +/*********************************************************************** + * Register the TVRX2 dboard + **********************************************************************/ +static dboard_base::sptr make_tvrx2(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new tvrx2(args)); +} + +UHD_STATIC_BLOCK(reg_tvrx2_dboard){ +    //register the factory function for the rx dbid +    dboard_manager::register_dboard(0x0046, &make_tvrx2, "TVRX2", tvrx2_sd_name_to_conn.keys()); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +tvrx2::tvrx2(ctor_args_t args) : rx_dboard_base(args){ +    //FIXME for USRP1, we can only support one TVRX2 installed + +    _rfcal_results = map_list_of +        (  0, tvrx2_tda18272_rfcal_result_t() ) +        (  1, tvrx2_tda18272_rfcal_result_t() ) +        (  2, tvrx2_tda18272_rfcal_result_t() ) +        (  3, tvrx2_tda18272_rfcal_result_t() ) +        (  4, tvrx2_tda18272_rfcal_result_t() ) +        (  5, tvrx2_tda18272_rfcal_result_t() ) +        (  6, tvrx2_tda18272_rfcal_result_t() ) +        (  7, tvrx2_tda18272_rfcal_result_t() ) +        (  8, tvrx2_tda18272_rfcal_result_t() ) +        (  9, tvrx2_tda18272_rfcal_result_t() ) +        ( 10, tvrx2_tda18272_rfcal_result_t() ) +        ( 11, tvrx2_tda18272_rfcal_result_t() ) +    ; + +    _rfcal_coeffs = map_list_of +        ( 0, tvrx2_tda18272_rfcal_coeffs_t(0) ) +        ( 1, tvrx2_tda18272_rfcal_coeffs_t(1) ) +        ( 2, tvrx2_tda18272_rfcal_coeffs_t(3) ) +        ( 3, tvrx2_tda18272_rfcal_coeffs_t(4) ) +        ( 4, tvrx2_tda18272_rfcal_coeffs_t(6) ) +        ( 5, tvrx2_tda18272_rfcal_coeffs_t(7) ) +        ( 6, tvrx2_tda18272_rfcal_coeffs_t(9) ) +        ( 7, tvrx2_tda18272_rfcal_coeffs_t(10) ) +    ; + +    //set defaults for LO, gains, and filter bandwidth +    _bandwidth = 10e6; + +    _if_freq = 12.5e6; + +    _enabled = false; + +    //send initial register settings +    //this->read_reg(0x0, 0x43); +    //this->send_reg(0x0, 0x43); + +    //send magic xtal_cal_dac setting +    send_reg(0x65, 0x65); + +    //////////////////////////////////////////////////////////////////// +    // Register properties +    //////////////////////////////////////////////////////////////////// +    this->get_rx_subtree()->create<std::string>("name") +        .set("TVRX2"); +    this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&tvrx2::get_locked, this)); +    this->get_rx_subtree()->create<sensor_value_t>("sensors/rssi") +        .publish(boost::bind(&tvrx2::get_rssi, this)); +    this->get_rx_subtree()->create<sensor_value_t>("sensors/temperature") +        .publish(boost::bind(&tvrx2::get_temp, this)); +    BOOST_FOREACH(const std::string &name, tvrx2_gain_ranges.keys()){ +        this->get_rx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&tvrx2::set_gain, this, _1, name)); +        this->get_rx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(tvrx2_gain_ranges[name]); +    } +    this->get_rx_subtree()->create<double>("freq/value") +        .coerce(boost::bind(&tvrx2::set_lo_freq, this, _1)); +    this->get_rx_subtree()->create<meta_range_t>("freq/range") +        .set(tvrx2_freq_range); +    this->get_rx_subtree()->create<std::string>("antenna/value") +        .set(tvrx2_sd_name_to_antennas[get_subdev_name()]); +    this->get_rx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(list_of(tvrx2_sd_name_to_antennas[get_subdev_name()])); +    this->get_rx_subtree()->create<std::string>("connection") +        .set(tvrx2_sd_name_to_conn[get_subdev_name()]); +    this->get_rx_subtree()->create<bool>("enabled") +        .coerce(boost::bind(&tvrx2::set_enabled, this, _1)) +        .set(_enabled); +    this->get_rx_subtree()->create<bool>("use_lo_offset") +        .set(false); +    this->get_rx_subtree()->create<double>("bandwidth/value") +        .coerce(boost::bind(&tvrx2::set_bandwidth, this, _1)) +        .set(_bandwidth); +    this->get_rx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(tvrx2_bandwidth_range); + +    //set the gpio directions and atr controls (identically) +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, 0); // All unused in atr +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, OUTPUT_MASK); // Set outputs + +    //configure ref_clock +    double ref_clock = this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX); + +    if (ref_clock == 64.0e6) { +        this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, REFCLOCK_DIV4); + +        UHD_LOGV(often) << boost::format( +            "TVRX2 (%s): Dividing Refclock by 4" +        ) % (get_subdev_name()) << std::endl; + +        _freq_scalar = (4*16.0e6)/(this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX)); +    } else if (ref_clock == 100e6) { +        this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, REFCLOCK_DIV6); + +        UHD_LOGV(often) << boost::format( +            "TVRX2 (%s): Dividing Refclock by 6" +        ) % (get_subdev_name()) << std::endl; + +        _freq_scalar = (6*16.0e6)/this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX); +    } else { +        this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, REFCLOCK_DIV6); +        UHD_MSG(warning) << boost::format("Unsupported ref_clock %0.2f, valid options 64e6 and 100e6") % ref_clock << std::endl; +        _freq_scalar = 1.0; +    } + +    //enable only the clocks we need +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_RX, true); + +    UHD_LOGV(often) << boost::format( +        "TVRX2 (%s): Refclock %f Hz, scalar = %f" +    ) % (get_subdev_name()) % (this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX)) % _freq_scalar << std::endl; + +    _tda18272hnm_regs.irq_polarity = tda18272hnm_regs_t::IRQ_POLARITY_RAISED_VCC; +    _tda18272hnm_regs.irq_clear = tda18272hnm_regs_t::IRQ_CLEAR_TRUE; +    send_reg(0x37, 0x37); +    send_reg(0xA, 0xA); + +    send_reg(0x31, 0x31); //N_CP_Current +    send_reg(0x36, 0x36); //RSSI_Clock +    send_reg(0x24, 0x25); //AGC1_Do_step +    send_reg(0x2C, 0x2C); //AGC1_Do_step +    send_reg(0x2E, 0x2E); //AGC2_Do_step +    send_reg(0x0E, 0x0E); //AGCs_Up_step_assym +    send_reg(0x11, 0x11); //AGCs_Do_step_assym + +    //intialize i2c +    //soft_calibration(); +    //tvrx2_tda18272_init_rfcal(); +    transition_0(); +} + +bool tvrx2::set_enabled(bool enable){ +    if (enable == _enabled) return _enabled; + +    if (enable and not _enabled){ +        //setup tuner parameters +        transition_1(); + +        transition_2(int(tvrx2_freq_range.start())); + +        test_rf_filter_robustness(); + +        BOOST_FOREACH(const std::string &name, tvrx2_gain_ranges.keys()){ +            this->get_rx_subtree()->access<double>("gains/"+name+"/value") +                .set(tvrx2_gain_ranges[name].start()); +        } + +        this->get_rx_subtree()->access<double>("bandwidth/value") +            .set(_bandwidth); // default bandwidth from datasheet + +        //transition_2 equivalent +        this->get_rx_subtree()->access<double>("freq/value") +            .set(tvrx2_freq_range.start()); + +        //enter standby mode +        transition_3(); +        _enabled = true; + +    } else { +        //enter standby mode +        transition_3(); +        _enabled = false; +    } + +    return _enabled; +} + +tvrx2::~tvrx2(void){ +    UHD_LOGV(often) << boost::format( +        "TVRX2 (%s): Called Destructor" +    ) % (get_subdev_name()) << std::endl; +    UHD_SAFE_CALL(if (_enabled) set_enabled(false);) +} + + +/*********************************************************************** + * TDA18272 Register IO Functions + **********************************************************************/ +void tvrx2::set_scaled_rf_freq(double rf_freq){ +    _tda18272hnm_regs.set_rf_freq(_freq_scalar*rf_freq/1e3); +} + +double tvrx2::get_scaled_rf_freq(void){ +    return _tda18272hnm_regs.get_rf_freq()*1e3/_freq_scalar; +} + +void tvrx2::set_scaled_if_freq(double if_freq){ +    _tda18272hnm_regs.if_freq = int(_freq_scalar*if_freq/(50e3)); //max 12.8MHz?? +} + +double tvrx2::get_scaled_if_freq(void){ +    return _tda18272hnm_regs.if_freq*50e3/_freq_scalar; +} + +void tvrx2::send_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg){ +    start_reg = boost::uint8_t(uhd::clip(int(start_reg), 0x0, 0x43)); +    stop_reg = boost::uint8_t(uhd::clip(int(stop_reg), 0x0, 0x43)); + +    for(boost::uint8_t start_addr=start_reg; start_addr <= stop_reg; start_addr += sizeof(boost::uint32_t) - 1){ +        int num_bytes = int(stop_reg - start_addr + 1) > int(sizeof(boost::uint32_t)) - 1 ? sizeof(boost::uint32_t) - 1 : stop_reg - start_addr + 1; + +        //create buffer for register data (+1 for start address) +        byte_vector_t regs_vector(num_bytes + 1); + +        //first byte is the address of first register +        regs_vector[0] = start_addr; + +        //get the register data +        for(int i=0; i<num_bytes; i++){ +            regs_vector[1+i] = _tda18272hnm_regs.get_reg(start_addr+i); +            UHD_LOGV(often) << boost::format( +                "TVRX2 (%s, 0x%02x): send reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" +            ) % (get_subdev_name()) % int(tvrx2_sd_name_to_i2c_addr[get_subdev_name()]) % int(start_addr+i) % int(regs_vector[1+i]) % int(start_addr) % num_bytes << std::endl; +        } + +        //send the data +        this->get_iface()->write_i2c( +            tvrx2_sd_name_to_i2c_addr[get_subdev_name()], regs_vector +        ); +    } +} + +void tvrx2::read_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg){ +    static const boost::uint8_t status_addr = 0x0; +    start_reg = boost::uint8_t(uhd::clip(int(start_reg), 0x0, 0x43)); +    stop_reg = boost::uint8_t(uhd::clip(int(stop_reg), 0x0, 0x43)); + +    for(boost::uint8_t start_addr=start_reg; start_addr <= stop_reg; start_addr += sizeof(boost::uint32_t)){ +        int num_bytes = int(stop_reg - start_addr + 1) > int(sizeof(boost::uint32_t)) ? sizeof(boost::uint32_t) : stop_reg - start_addr + 1; + +        //create buffer for starting address +        byte_vector_t start_address_vector(1); + +        //first byte is the address of first register +        start_address_vector[0] = start_addr; + +        //send the start address +        this->get_iface()->write_i2c( +            tvrx2_sd_name_to_i2c_addr[get_subdev_name()], start_address_vector +        ); + +        //create buffer for register data +        byte_vector_t regs_vector(num_bytes); + +        //read from i2c +        regs_vector = this->get_iface()->read_i2c( +            tvrx2_sd_name_to_i2c_addr[get_subdev_name()], num_bytes +        ); + +        for(boost::uint8_t i=0; i < num_bytes; i++){ +            if (i + start_addr >= status_addr){ +                _tda18272hnm_regs.set_reg(i + start_addr, regs_vector[i]); +            } +            UHD_LOGV(often) << boost::format( +                "TVRX2 (%s, 0x%02x): read reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" +            ) % (get_subdev_name()) % int(tvrx2_sd_name_to_i2c_addr[get_subdev_name()]) % int(start_addr+i) % int(regs_vector[i]) % int(start_addr) % num_bytes << std::endl; +        } +    } +} + + +/*********************************************************************** + * TDA18272 Calibration Functions + **********************************************************************/ +freq_range_t tvrx2::get_tda18272_rfcal_result_freq_range(boost::uint32_t result) +{ + +    uhd::dict<boost::uint32_t, freq_range_t> result_to_cal_freq_ranges_map = map_list_of +        ( 0, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[0].cal_freq[_tda18272hnm_regs.rfcal_freq0] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[1].cal_freq[_tda18272hnm_regs.rfcal_freq1] * _freq_scalar +                 ) ) +        ( 1, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[1].cal_freq[_tda18272hnm_regs.rfcal_freq1] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[2].cal_freq[_tda18272hnm_regs.rfcal_freq2] * _freq_scalar +                 ) ) +        ( 2, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[2].cal_freq[_tda18272hnm_regs.rfcal_freq2] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[3].cal_freq[_tda18272hnm_regs.rfcal_freq3] * _freq_scalar +                 ) ) +        ( 3, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[3].cal_freq[_tda18272hnm_regs.rfcal_freq3] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[4].cal_freq[_tda18272hnm_regs.rfcal_freq4] * _freq_scalar +                 ) ) +        ( 4, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[4].cal_freq[_tda18272hnm_regs.rfcal_freq4] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[5].cal_freq[_tda18272hnm_regs.rfcal_freq5] * _freq_scalar +                 ) ) +        ( 5, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[5].cal_freq[_tda18272hnm_regs.rfcal_freq5] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[6].cal_freq[_tda18272hnm_regs.rfcal_freq6] * _freq_scalar +                 ) ) +        ( 6, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[6].cal_freq[_tda18272hnm_regs.rfcal_freq6] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[7].cal_freq[_tda18272hnm_regs.rfcal_freq7] * _freq_scalar +                 ) ) +        ( 7, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[7].cal_freq[_tda18272hnm_regs.rfcal_freq7] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[8].cal_freq[_tda18272hnm_regs.rfcal_freq8] * _freq_scalar +                 ) ) +        ( 8, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[8].cal_freq[_tda18272hnm_regs.rfcal_freq8] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[9].cal_freq[_tda18272hnm_regs.rfcal_freq9] * _freq_scalar +                 ) ) +        ( 9, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[9].cal_freq[_tda18272hnm_regs.rfcal_freq9] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[10].cal_freq[_tda18272hnm_regs.rfcal_freq10] * _freq_scalar +                 ) ) +        (10, freq_range_t( +                 (double) tvrx2_tda18272_cal_map[10].cal_freq[_tda18272hnm_regs.rfcal_freq10] * _freq_scalar, +                 (double) tvrx2_tda18272_cal_map[11].cal_freq[_tda18272hnm_regs.rfcal_freq11] * _freq_scalar +                 ) ) +    ; + +    if (result < 11) +        return result_to_cal_freq_ranges_map[result];  +    else +        return freq_range_t(0.0, 0.0); +} + + +/* + * Initialize the RF Filter calibration maps after hardware init + */ +void tvrx2::tvrx2_tda18272_init_rfcal(void) +{ + +    /* read byte 0x38-0x43 */ +    read_reg(0x38, 0x43); + +    uhd::dict<boost::uint32_t, boost::uint8_t> result_to_cal_regs = map_list_of +        ( 0, _tda18272hnm_regs.rfcal_log_1) +        ( 1, _tda18272hnm_regs.rfcal_log_2) +        ( 2, _tda18272hnm_regs.rfcal_log_3) +        ( 3, _tda18272hnm_regs.rfcal_log_4) +        ( 4, _tda18272hnm_regs.rfcal_log_5) +        ( 5, _tda18272hnm_regs.rfcal_log_6) +        ( 6, _tda18272hnm_regs.rfcal_log_7) +        ( 7, _tda18272hnm_regs.rfcal_log_8) +        ( 8, _tda18272hnm_regs.rfcal_log_9) +        ( 9, _tda18272hnm_regs.rfcal_log_10) +        (10, _tda18272hnm_regs.rfcal_log_11) +        (11, _tda18272hnm_regs.rfcal_log_12) +    ; + + +    // Loop through rfcal_log_* registers, initialize _rfcal_results +    BOOST_FOREACH(const boost::uint32_t &result, result_to_cal_regs.keys()) +        _rfcal_results[result].delta_c = result_to_cal_regs[result] > 63 ? result_to_cal_regs[result] - 128 : result_to_cal_regs[result]; + +    /* read byte 0x26-0x2B */ +    read_reg(0x26, 0x2B); + +    // Loop through rfcal_byte_* registers, initialize _rfcal_coeffs +    BOOST_FOREACH(const boost::uint32_t &subband, _rfcal_coeffs.keys()) +    { +        freq_range_t subband_freqs; + +        boost::uint32_t result = _rfcal_coeffs[subband].cal_number; + +        subband_freqs = get_tda18272_rfcal_result_freq_range(result); + +        _rfcal_coeffs[subband].RF_B1 = _rfcal_results[result].delta_c + tvrx2_tda18272_cal_map[result].c_offset[_rfcal_results[result].c_offset]; + +        boost::uint32_t quotient = (((_rfcal_results[result+1].delta_c + tvrx2_tda18272_cal_map[result+1].c_offset[_rfcal_results[result].c_offset]) +                                        - (_rfcal_results[result].delta_c + tvrx2_tda18272_cal_map[result].c_offset[_rfcal_results[result].c_offset])) * 1000000); + +        boost::uint32_t divisor = ((boost::int32_t)(subband_freqs.stop() - subband_freqs.start())/1000); + +        _rfcal_coeffs[subband].RF_A1 = quotient / divisor; + +    } + +} + +/* + * Apply calibration coefficients to RF Filter tuning + */ +void tvrx2::tvrx2_tda18272_tune_rf_filter(boost::uint32_t uRF) +{ +    boost::uint32_t                  uCounter = 0; +    boost::uint8_t                   cal_result = 0; +    boost::uint32_t                  uRFCal0 = 0; +    boost::uint32_t                  uRFCal1 = 0; +    boost::uint8_t                   subband = 0; +    boost::int32_t                   cProg = 0; +    boost::uint8_t                   gain_taper = 0; +    boost::uint8_t                   RFBand = 0; +    boost::int32_t                   RF_A1 = 0; +    boost::int32_t                   RF_B1 = 0; +    freq_range_t                     subband_freqs; + +    /* read byte 0x26-0x2B */ +    read_reg(0x26, 0x2B); + +    subband_freqs = get_tda18272_rfcal_result_freq_range(1); +    uRFCal0 = subband_freqs.start(); +    subband_freqs = get_tda18272_rfcal_result_freq_range(4); +    uRFCal1 = subband_freqs.start(); + +    if(uRF < uRFCal0) +        subband = 0; +    else if(uRF < 145700000) +        subband = 1; +    else if(uRF < uRFCal1) +        subband = 2; +    else if(uRF < 367400000) +        subband = 3; +    else +    { +        subband_freqs = get_tda18272_rfcal_result_freq_range(7); +        uRFCal0 = subband_freqs.start(); +        subband_freqs = get_tda18272_rfcal_result_freq_range(10); +        uRFCal1 = subband_freqs.start(); + +        if(uRF < uRFCal0) +            subband = 4; +        else if(uRF < 625000000) +            subband = 5; +        else if(uRF < uRFCal1) +            subband = 6; +        else +            subband = 7; +    } + +    cal_result = _rfcal_coeffs[subband].cal_number; +    subband_freqs = get_tda18272_rfcal_result_freq_range(cal_result); +    uRFCal0 = subband_freqs.start(); + +    RF_A1 = _rfcal_coeffs[subband].RF_A1; +    RF_B1 = _rfcal_coeffs[subband].RF_B1; + +    uCounter = 0; +    do uCounter ++; +    while (uRF >= tvrx2_tda18272_freq_map[uCounter].rf_max && uCounter < TVRX2_TDA18272_FREQ_MAP_ENTRIES); + +    cProg = tvrx2_tda18272_freq_map[uCounter - 1].c_prog; +    gain_taper = tvrx2_tda18272_freq_map[uCounter - 1].gain_taper; +    RFBand = tvrx2_tda18272_freq_map[uCounter - 1].rf_band; + +    cProg = (boost::int32_t)(cProg + RF_B1 + (RF_A1*((boost::int32_t)(uRF - uRFCal0)/1000))/1000000); + +    if(cProg>255)   cProg = 255; +    if(cProg<0)     cProg = 0; + +    _tda18272hnm_regs.rf_filter_bypass = 1; +    _tda18272hnm_regs.rf_filter_cap = (boost::uint8_t) cProg; +    _tda18272hnm_regs.gain_taper = gain_taper; +    _tda18272hnm_regs.rf_filter_band = RFBand; + +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): Software Calibration:\n" +        "\tRF Filter Bypass = %d\n" +        "\tRF Filter Cap    = %d\n" +        "\tRF Filter Band   = %d\n" +        "\tGain Taper       = %d\n")  +        % (get_subdev_name()) +        % int(_tda18272hnm_regs.rf_filter_bypass) +        % int(_tda18272hnm_regs.rf_filter_cap) +        % int(_tda18272hnm_regs.rf_filter_band)  +        % int(_tda18272hnm_regs.gain_taper) +        << std::endl; + +    send_reg(0x2c, 0x2f); +} + +void tvrx2::soft_calibration(void){ +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): Software Calibration: Initialize Tuner, Calibrate and Standby\n") % (get_subdev_name()) << std::endl; + +    _tda18272hnm_regs.sm = tda18272hnm_regs_t::SM_NORMAL; +    _tda18272hnm_regs.sm_lna = tda18272hnm_regs_t::SM_LNA_ON; +    _tda18272hnm_regs.sm_pll = tda18272hnm_regs_t::SM_PLL_ON; + +    send_reg(0x6, 0x6); +    read_reg(0x6, 0x6); + +    read_reg(0x19, 0x1A); +    read_reg(0x26, 0x2B); + +    _tda18272hnm_regs.rfcal_freq0  = 0x2; +    _tda18272hnm_regs.rfcal_freq1  = 0x2; +    _tda18272hnm_regs.rfcal_freq2  = 0x2; +    _tda18272hnm_regs.rfcal_freq3  = 0x2; +    _tda18272hnm_regs.rfcal_freq4  = 0x2; +    _tda18272hnm_regs.rfcal_freq5  = 0x2; +    _tda18272hnm_regs.rfcal_freq6  = 0x2; +    _tda18272hnm_regs.rfcal_freq7  = 0x2; +    _tda18272hnm_regs.rfcal_freq8  = 0x2; +    _tda18272hnm_regs.rfcal_freq9  = 0x2; +    _tda18272hnm_regs.rfcal_freq10 = 0x2; +    _tda18272hnm_regs.rfcal_freq11 = 0x2; + +    send_reg(0x26, 0x2B); + +    _tda18272hnm_regs.set_reg(0x19, 0x3B); //set MSM_byte_1 for calibration per datasheet +    _tda18272hnm_regs.set_reg(0x1A, 0x01); //set MSM_byte_2 for launching calibration + +    send_reg(0x19, 0x1A); + +    wait_irq(); + +    send_reg(0x1D, 0x1D); //Fmax_LO +    send_reg(0x0C, 0x0C); //LT_Enable +    send_reg(0x1B, 0x1B); //PSM_AGC1 +    send_reg(0x0C, 0x0C); //AGC1_6_15dB + +    //set spread spectrum for clock  +    //FIXME: NXP turns clock spread on and off  +    //   based on where clock spurs would be relative to RF frequency +    //   we should do this also +    _tda18272hnm_regs.digital_clock = tda18272hnm_regs_t::DIGITAL_CLOCK_SPREAD_OFF; +    if (get_subdev_name() == "RX1") +        //_tda18272hnm_regs.xtout = tda18272hnm_regs_t::XTOUT_NO; +        _tda18272hnm_regs.xtout = tda18272hnm_regs_t::XTOUT_16MHZ; +    else +        //_tda18272hnm_regs.xtout = tda18272hnm_regs_t::XTOUT_NO; +        _tda18272hnm_regs.xtout = tda18272hnm_regs_t::XTOUT_16MHZ; +     +    send_reg(0x14, 0x14); + +    _tda18272hnm_regs.set_reg(0x36, 0x0E); //sets clock mode +    send_reg(0x36, 0x36); + +    //go to standby mode +    _tda18272hnm_regs.sm = tda18272hnm_regs_t::SM_STANDBY; +    send_reg(0x6, 0x6); +} + +void tvrx2::test_rf_filter_robustness(void){ +    typedef uhd::dict<std::string, std::string> tvrx2_filter_ratings_t; +    typedef uhd::dict<std::string, double> tvrx2_filter_margins_t; + +    tvrx2_filter_margins_t _filter_margins; +    tvrx2_filter_ratings_t _filter_ratings; + +    read_reg(0x38, 0x43); + +    uhd::dict<std::string, boost::uint8_t> filter_cal_regs = map_list_of +        ("VHFLow_0", 0x38) +        ("VHFLow_1", 0x3a) +        ("VHFHigh_0", 0x3b) +        ("VHFHigh_1", 0x3d) +        ("UHFLow_0", 0x3e) +        ("UHFLow_1", 0x40) +        ("UHFHigh_0", 0x41) +        ("UHFHigh_1", 0x43) +    ; + +    BOOST_FOREACH(const std::string &name, filter_cal_regs.keys()){ +        boost::uint8_t cal_result = _tda18272hnm_regs.get_reg(filter_cal_regs[name]); +        if (cal_result & 0x80) { +            _filter_ratings.set(name, "E"); +            _filter_margins.set(name, 0.0); +        } +        else { +            double partial; + +            if (name == "VHFLow_0") +                partial = 100 * (45 - 39.8225 * (1 + (0.31 * (cal_result < 64 ? cal_result : cal_result - 128)) / 1.0 / 100.0)) / 45.0; + +            else if (name == "VHFLow_1") +                partial = 100 * (152.1828 * (1 + (1.53 * (cal_result < 64 ? cal_result : cal_result - 128)) / 1.0 / 100.0) - (144.896 - 6)) / (144.896 - 6);  + +            else if (name == "VHFHigh_0") +                partial = 100 * ((144.896 + 6) - 135.4063 * (1 + (0.27 * (cal_result < 64 ? cal_result : cal_result - 128)) / 1.0 / 100.0)) / (144.896 + 6); + +            else if (name == "VHFHigh_1") +                partial = 100 * (383.1455 * (1 + (0.91 * (cal_result < 64 ? cal_result : cal_result - 128)) / 1.0 / 100.0) - (367.104 - 8)) / (367.104 - 8); + +            else if (name == "UHFLow_0") +                partial = 100 * ((367.104 + 8) - 342.6224 * (1 + (0.21 * (cal_result < 64 ? cal_result : cal_result - 128)) / 1.0 / 100.0)) / (367.104 + 8); + +            else if (name == "UHFLow_1") +                partial = 100 * (662.5595 * (1 + (0.33 * (cal_result < 64 ? cal_result : cal_result - 128)) / 1.0 / 100.0) - (624.128 - 2)) / (624.128 - 2); + +            else if (name == "UHFHigh_0") +                partial = 100 * ((624.128 + 2) - 508.2747 * (1 + (0.23 * (cal_result < 64 ? cal_result : cal_result - 128)) / 1.0 / 100.0)) / (624.128 + 2); + +            else if (name == "UHFHigh_1") +                partial = 100 * (947.8913 * (1 + (0.3 * (cal_result < 64 ? cal_result : cal_result - 128)) / 1.0 / 100.0) - (866 - 14)) / (866 - 14); + +            else +                UHD_THROW_INVALID_CODE_PATH(); + +            _filter_margins.set(name, 0.0024 * partial * partial * partial - 0.101 * partial * partial + 1.629 * partial + 1.8266); +            _filter_ratings.set(name, _filter_margins[name] >= 0.0 ? "H" : "L"); +        } +    } + +    std::stringstream robustness_message; +    robustness_message << boost::format("TVRX2 (%s): RF Filter Robustness Results:") % (get_subdev_name()) << std::endl; +    BOOST_FOREACH(const std::string &name, uhd::sorted(_filter_ratings.keys())){ +        robustness_message << boost::format("\t%s:\tMargin = %0.2f,\tRobustness = %c") % name % (_filter_margins[name]) % (_filter_ratings[name]) << std::endl; +    } + +    UHD_LOGV(often) << robustness_message.str(); +} + +/*********************************************************************** + * TDA18272 State Functions + **********************************************************************/ +void tvrx2::transition_0(void){ +    //Transition 0: Initialize Tuner and place in standby +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): Transistion 0: Initialize Tuner, Calibrate and Standby\n") % (get_subdev_name()) << std::endl; + +    //Check for Power-On Reset, if reset, initialze tuner +    if (get_power_reset()) { +        _tda18272hnm_regs.sm = tda18272hnm_regs_t::SM_NORMAL; +        _tda18272hnm_regs.sm_lna = tda18272hnm_regs_t::SM_LNA_ON; +        _tda18272hnm_regs.sm_pll = tda18272hnm_regs_t::SM_PLL_ON; + +        send_reg(0x6, 0x6); +        read_reg(0x6, 0x6); + +        read_reg(0x19, 0x1A); + +        _tda18272hnm_regs.set_reg(0x19, 0x3B); //set MSM_byte_1 for calibration per datasheet +        _tda18272hnm_regs.set_reg(0x1A, 0x01); //set MSM_byte_2 for launching calibration + +        send_reg(0x19, 0x1A); + +        wait_irq(); +    } + +    //send magic xtal_cal_dac setting +    send_reg(0x65, 0x65); + +    send_reg(0x1D, 0x1D); //Fmax_LO +    send_reg(0x0C, 0x0C); //LT_Enable +    send_reg(0x1B, 0x1B); //PSM_AGC1 +    send_reg(0x0C, 0x0C); //AGC1_6_15dB + +    //set spread spectrum for clock  +    //FIXME: NXP turns clock spread on and off  +    //   based on where clock spurs would be relative to RF frequency +    //   we should do this also +    _tda18272hnm_regs.digital_clock = tda18272hnm_regs_t::DIGITAL_CLOCK_SPREAD_OFF; +    if (get_subdev_name() == "RX1") +        //_tda18272hnm_regs.xtout = tda18272hnm_regs_t::XTOUT_NO; +        _tda18272hnm_regs.xtout = tda18272hnm_regs_t::XTOUT_16MHZ; +    else +        //_tda18272hnm_regs.xtout = tda18272hnm_regs_t::XTOUT_NO; +        _tda18272hnm_regs.xtout = tda18272hnm_regs_t::XTOUT_16MHZ; +     +    send_reg(0x14, 0x14); + +    _tda18272hnm_regs.set_reg(0x36, 0x0E); //sets clock mode +    send_reg(0x36, 0x36); + +    //go to standby mode +    _tda18272hnm_regs.sm = tda18272hnm_regs_t::SM_STANDBY; +    send_reg(0x6, 0x6); +} + +void tvrx2::transition_1(void){ +    //Transition 1: Select TV Standard +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): Transistion 1: Select TV Standard\n") % (get_subdev_name()) << std::endl; + +    //send magic xtal_cal_dac setting +    send_reg(0x65, 0x65); + +    //Choose IF Byte 1 Setting +    //_tda18272hnm_regs.if_hp_fc = tda18272hnm_regs_t::IF_HP_FC_0_4MHZ; +    //_tda18272hnm_regs.if_notch = tda18272hnm_regs_t::IF_NOTCH_OFF; +    //_tda18272hnm_regs.lp_fc_offset = tda18272hnm_regs_t::LP_FC_OFFSET_0_PERCENT; +    //_tda18272hnm_regs.lp_fc = tda18272hnm_regs_t::LP_FC_10_0MHZ; +    //send_reg(0x13, 0x13); + +    //Choose IR Mixer Byte 2 Setting +    //_tda18272hnm_regs.hi_pass = tda18272hnm_regs_t::HI_PASS_DISABLE; +    //_tda18272hnm_regs.dc_notch = tda18272hnm_regs_t::DC_NOTCH_OFF; +    send_reg(0x23, 0x23); + +    //Set AGC TOP Bytes +    send_reg(0x0C, 0x13); + +    //Set PSM Byt1 +    send_reg(0x1B, 0x1B); + +    //Choose IF Frequency, setting is 50KHz steps +    set_scaled_if_freq(_if_freq); +    send_reg(0x15, 0x15); +} + +void tvrx2::transition_2(int rf_freq){ +    //Transition 2: Select RF Frequency after changing TV Standard +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): Transistion 2: Select RF Frequency after changing TV Standard\n") % (get_subdev_name()) << std::endl; + +    //send magic xtal_cal_dac setting +    send_reg(0x65, 0x65); + +    //Wake up from Standby +    _tda18272hnm_regs.sm = tda18272hnm_regs_t::SM_NORMAL; +    _tda18272hnm_regs.sm_lna = tda18272hnm_regs_t::SM_LNA_ON; +    _tda18272hnm_regs.sm_pll = tda18272hnm_regs_t::SM_PLL_ON; +     +    send_reg(0x6, 0x6); +     +    //Set Clock Mode +    _tda18272hnm_regs.set_reg(0x36, 0x00); +    send_reg(0x36, 0x36); +     +    //Set desired RF Frequency +    set_scaled_rf_freq(rf_freq); +    send_reg(0x16, 0x18); +     +    //Lock PLL and tune RF Filters +    _tda18272hnm_regs.set_reg(0x19, 0x41); //set MSM_byte_1 for RF Filters Tuning, PLL Locking +    _tda18272hnm_regs.set_reg(0x1A, 0x01); //set MSM_byte_2 for launching calibration +     +    send_reg(0x19, 0x1A); +     +    wait_irq(); + +    tvrx2_tda18272_tune_rf_filter(rf_freq); + +    ////LO Lock state in Reg 0x5 LSB +    //read_reg(0x6, 0x6); + +} + +void tvrx2::transition_3(void){ +    //Transition 3: Standby Mode +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): Transistion 3: Standby Mode\n") % (get_subdev_name()) << std::endl; + +    //send magic xtal_cal_dac setting +    send_reg(0x65, 0x65); + +    //Set clock mode +    _tda18272hnm_regs.set_reg(0x36, 0x0E); +    send_reg(0x36, 0x36); + +    //go to standby mode +    _tda18272hnm_regs.sm = tda18272hnm_regs_t::SM_STANDBY; +    _tda18272hnm_regs.sm_lna = tda18272hnm_regs_t::SM_LNA_OFF; +    _tda18272hnm_regs.sm_pll = tda18272hnm_regs_t::SM_PLL_OFF; +    send_reg(0x6, 0x6); +} + +void tvrx2::transition_4(int rf_freq){ +    //Transition 4: Change RF Frequency without changing TV Standard +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): Transistion 4: Change RF Frequency without changing TV Standard\n") % (get_subdev_name()) << std::endl; + +    //send magic xtal_cal_dac setting +    send_reg(0x65, 0x65); + +    //Set desired RF Frequency +    set_scaled_rf_freq(rf_freq); +    send_reg(0x16, 0x18); +     +    //Lock PLL and tune RF Filters +    _tda18272hnm_regs.set_reg(0x19, 0x41); //set MSM_byte_1 for RF Filters Tuning, PLL Locking +    _tda18272hnm_regs.set_reg(0x1A, 0x01); //set MSM_byte_2 for launching calibration +     +    send_reg(0x19, 0x1A); +     +    wait_irq(); + +    tvrx2_tda18272_tune_rf_filter(rf_freq); + +    ////LO Lock state in Reg 0x5 LSB +    //read_reg(0x5, 0x6); + +} + +void tvrx2::wait_irq(void){ +    int timeout = 20; //irq waiting timeout in milliseconds +    //int irq = (this->get_iface()->read_gpio(dboard_iface::UNIT_RX) & int(tvrx2_sd_name_to_irq_io[get_subdev_name()])); +    bool irq = get_irq(); +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): Waiting on IRQ, subdev = %d, mask = 0x%x, Status: 0x%x\n") % (get_subdev_name()) % get_subdev_name() % (int(tvrx2_sd_name_to_irq_io[get_subdev_name()])) % irq << std::endl; + +    while (not irq and timeout > 0) { +        //irq = (this->get_iface()->read_gpio(dboard_iface::UNIT_RX) & tvrx2_sd_name_to_irq_io[get_subdev_name()]); +        irq = get_irq(); +        boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +        timeout -= 1; +    } + +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): IRQ Raised, subdev = %d, mask = 0x%x, Status: 0x%x, Timeout: %d\n") % (get_subdev_name()) % get_subdev_name() % (int(tvrx2_sd_name_to_irq_io[get_subdev_name()])) % irq % timeout << std::endl; + +    read_reg(0xA, 0xB); +    //UHD_ASSERT_THROW(timeout > 0); +    if(timeout <= 0) UHD_MSG(warning) << boost::format( +        "\nTVRX2 (%s): Timeout waiting on IRQ\n") % (get_subdev_name()) << std::endl; + +    _tda18272hnm_regs.irq_clear = tda18272hnm_regs_t::IRQ_CLEAR_TRUE; +    send_reg(0xA, 0xA); +    read_reg(0xA, 0xB); + +    irq = (this->get_iface()->read_gpio(dboard_iface::UNIT_RX) & tvrx2_sd_name_to_irq_io[get_subdev_name()]); + +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): Cleared IRQ, subdev = %d, mask = 0x%x, Status: 0x%x\n") % (get_subdev_name()) % get_subdev_name() % (int(tvrx2_sd_name_to_irq_io[get_subdev_name()])) % irq << std::endl; +} + + + +/*********************************************************************** + * Tuning + **********************************************************************/ +double tvrx2::set_lo_freq(double target_freq){ +    //target_freq = std::clip(target_freq, tvrx2_freq_range.min, tvrx2_freq_range.max); + +    read_reg(0x6, 0x6); + +    if (_tda18272hnm_regs.sm == tda18272hnm_regs_t::SM_STANDBY) { +        transition_2(int(target_freq + _bandwidth/2 - get_scaled_if_freq())); +    } else { +        transition_4(int(target_freq + _bandwidth/2 - get_scaled_if_freq())); +    } +    read_reg(0x16, 0x18); + +    //compute actual tuned frequency +    _lo_freq = get_scaled_rf_freq() + get_scaled_if_freq(); // - _bandwidth/2; + +    //debug output of calculated variables +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): LO Frequency\n" +        "\tRequested: \t%f\n" +        "\tComputed: \t%f\n" +        "\tReadback: \t%f\n" +        "\tIF Frequency: \t%f\n") % (get_subdev_name()) % target_freq % double(int(target_freq/1e3)*1e3) % get_scaled_rf_freq() % get_scaled_if_freq() << std::endl; + +    get_locked(); + +    test_rf_filter_robustness(); + +    UHD_LOGV(often) << boost::format( +        "\nTVRX2 (%s): RSSI = %f dBm\n" +    ) % (get_subdev_name()) % (get_rssi().to_real()) << std::endl; + +    return _lo_freq; +} + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +/* + * Convert the requested gain into a dac voltage + */ +static double gain_to_if_gain_dac(double &gain){ +    //clip the input +    gain = tvrx2_gain_ranges["IF"].clip(gain); + +    //voltage level constants +    static const double max_volts = double(1.7), min_volts = double(0.5); +    static const double slope = (max_volts-min_volts)/tvrx2_gain_ranges["IF"].stop(); + +    //calculate the voltage for the aux dac +    double dac_volts = gain*slope + min_volts; + +    UHD_LOGV(often) << boost::format( +        "TVRX2 IF Gain: %f dB, dac_volts: %f V" +    ) % gain % dac_volts << std::endl; + +    //the actual gain setting +    gain = (dac_volts - min_volts)/slope; + +    return dac_volts; +} + +double tvrx2::set_gain(double gain, const std::string &name){ +    assert_has(tvrx2_gain_ranges.keys(), name, "tvrx2 gain name"); + +    if (name == "IF"){ +        //write voltage to aux_dac +        this->get_iface()->write_aux_dac(dboard_iface::UNIT_RX, tvrx2_sd_name_to_dac[get_subdev_name()], gain_to_if_gain_dac(gain)); +    } +    else UHD_THROW_INVALID_CODE_PATH(); + +    //shadow gain setting +    _gains[name] = gain; + +    return gain; +} + +/*********************************************************************** + * Bandwidth Handling + **********************************************************************/ +static tda18272hnm_regs_t::lp_fc_t bandwidth_to_lp_fc_reg(double &bandwidth){ +    int reg = uhd::clip(boost::math::iround((bandwidth-5.0e6)/1.0e6), 0, 4); + +    switch(reg){ +    case 0: +        bandwidth = 1.7e6; +        return tda18272hnm_regs_t::LP_FC_1_7MHZ; +    case 1: +        bandwidth = 6e6; +        return tda18272hnm_regs_t::LP_FC_6_0MHZ; +    case 2: +        bandwidth = 7e6; +        return tda18272hnm_regs_t::LP_FC_7_0MHZ; +    case 3: +        bandwidth = 8e6; +        return tda18272hnm_regs_t::LP_FC_8_0MHZ; +    case 4: +        bandwidth = 10e6; +        return tda18272hnm_regs_t::LP_FC_10_0MHZ; +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +double tvrx2::set_bandwidth(double bandwidth){ +    //clip the input +    bandwidth = tvrx2_bandwidth_range.clip(bandwidth); + +    //compute low pass cutoff frequency setting +    _tda18272hnm_regs.lp_fc = bandwidth_to_lp_fc_reg(bandwidth); + +    //shadow bandwidth setting +    _bandwidth = bandwidth; + +    //update register +    send_reg(0x13, 0x13); + +    UHD_LOGV(often) << boost::format( +        "TVRX2 (%s) Bandwidth (lp_fc): %f Hz, reg: %d" +    ) % (get_subdev_name()) % _bandwidth % (int(_tda18272hnm_regs.lp_fc)) << std::endl; + +    return _bandwidth; +} diff --git a/host/lib/usrp/dboard/db_unknown.cpp b/host/lib/usrp/dboard/db_unknown.cpp new file mode 100644 index 000000000..2ed50cd91 --- /dev/null +++ b/host/lib/usrp/dboard/db_unknown.cpp @@ -0,0 +1,160 @@ +// +// 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/types/ranges.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/foreach.hpp> +#include <boost/tuple/tuple.hpp> +#include <vector> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +/*********************************************************************** + * Utility functions + **********************************************************************/ +static void warn_if_old_rfx(const dboard_id_t &dboard_id, const std::string &xx){ +    typedef boost::tuple<std::string, dboard_id_t, dboard_id_t> old_ids_t; //name, rx_id, tx_id +    static const std::vector<old_ids_t> old_rfx_ids = list_of +        (old_ids_t("Flex 400 Classic",  0x0004, 0x0008)) +        (old_ids_t("Flex 900 Classic",  0x0005, 0x0009)) +        (old_ids_t("Flex 1200 Classic", 0x0006, 0x000a)) +        (old_ids_t("Flex 1800 Classic", 0x0030, 0x0031)) +        (old_ids_t("Flex 2400 Classic", 0x0007, 0x000b)) +    ; +    BOOST_FOREACH(const old_ids_t &old_id, old_rfx_ids){ +        std::string name; dboard_id_t rx_id, tx_id; +        boost::tie(name, rx_id, tx_id) = old_id; +        if ( +            (xx == "RX" and rx_id == dboard_id) or +            (xx == "TX" and tx_id == dboard_id) +        ) UHD_MSG(warning) << boost::format( +            "Detected %s daughterboard %s\n" +            "This board requires modification to use.\n" +            "See the daughterboard application notes.\n" +        ) % xx % name; +    } +} + +/*********************************************************************** + * The unknown boards: + *   Like a basic board, but with only one subdev. + **********************************************************************/ +class unknown_rx : public rx_dboard_base{ +public: +    unknown_rx(ctor_args_t args); +}; + +class unknown_tx : public tx_dboard_base{ +public: +    unknown_tx(ctor_args_t args); +}; + +/*********************************************************************** + * Register the unknown dboards + **********************************************************************/ +static dboard_base::sptr make_unknown_rx(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new unknown_rx(args)); +} + +static dboard_base::sptr make_unknown_tx(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new unknown_tx(args)); +} + +UHD_STATIC_BLOCK(reg_unknown_dboards){ +    dboard_manager::register_dboard(0xfff0, &make_unknown_tx, "Unknown TX"); +    dboard_manager::register_dboard(0xfff1, &make_unknown_rx, "Unknown RX"); +} + +/*********************************************************************** + * Unknown RX dboard + **********************************************************************/ +unknown_rx::unknown_rx(ctor_args_t args) : rx_dboard_base(args){ +    warn_if_old_rfx(this->get_rx_id(), "RX"); + +    //////////////////////////////////////////////////////////////////// +    // Register properties +    //////////////////////////////////////////////////////////////////// +    this->get_rx_subtree()->create<std::string>("name").set( +        std::string(str(boost::format("%s - %s") +            % get_rx_id().to_pp_string() +            % get_subdev_name() +        ))); +    this->get_rx_subtree()->create<int>("gains"); //phony property so this dir exists +    this->get_rx_subtree()->create<double>("freq/value") +        .set(double(0.0)); +    this->get_rx_subtree()->create<meta_range_t>("freq/range") +        .set(freq_range_t(double(0.0), double(0.0))); +    this->get_rx_subtree()->create<std::string>("antenna/value") +        .set(""); +    this->get_rx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(list_of("")); +    this->get_rx_subtree()->create<int>("sensors"); //phony property so this dir exists +    this->get_rx_subtree()->create<std::string>("connection") +        .set("IQ"); +    this->get_rx_subtree()->create<bool>("enabled") +        .set(true); //always enabled +    this->get_rx_subtree()->create<bool>("use_lo_offset") +        .set(false); +    this->get_rx_subtree()->create<double>("bandwidth/value") +        .set(double(0.0)); +    this->get_rx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(0.0, 0.0)); +} + +/*********************************************************************** + * Unknown TX dboard + **********************************************************************/ +unknown_tx::unknown_tx(ctor_args_t args) : tx_dboard_base(args){ +    warn_if_old_rfx(this->get_tx_id(), "TX"); + +    //////////////////////////////////////////////////////////////////// +    // Register properties +    //////////////////////////////////////////////////////////////////// +    this->get_tx_subtree()->create<std::string>("name").set( +        std::string(str(boost::format("%s - %s") +            % get_tx_id().to_pp_string() +            % get_subdev_name() +        ))); +    this->get_tx_subtree()->create<int>("gains"); //phony property so this dir exists +    this->get_tx_subtree()->create<double>("freq/value") +        .set(double(0.0)); +    this->get_tx_subtree()->create<meta_range_t>("freq/range") +        .set(freq_range_t(double(0.0), double(0.0))); +    this->get_tx_subtree()->create<std::string>("antenna/value") +        .set(""); +    this->get_tx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(list_of("")); +    this->get_tx_subtree()->create<int>("sensors"); //phony property so this dir exists +    this->get_tx_subtree()->create<std::string>("connection") +        .set("IQ"); +    this->get_tx_subtree()->create<bool>("enabled") +        .set(true); //always enabled +    this->get_tx_subtree()->create<bool>("use_lo_offset") +        .set(false); +    this->get_tx_subtree()->create<double>("bandwidth/value") +        .set(double(0.0)); +    this->get_tx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(0.0, 0.0)); +} diff --git a/host/lib/usrp/dboard/db_wbx_common.cpp b/host/lib/usrp/dboard/db_wbx_common.cpp new file mode 100644 index 000000000..58ce03d79 --- /dev/null +++ b/host/lib/usrp/dboard/db_wbx_common.cpp @@ -0,0 +1,152 @@ +// +// 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 "db_wbx_common.hpp" +#include "adf4350_regs.hpp" +#include <uhd/types/dict.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/utils/msg.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + + +/*********************************************************************** + * Gain-related functions + **********************************************************************/ +static int rx_pga0_gain_to_iobits(double &gain){ +    //clip the input +    gain = wbx_rx_gain_ranges["PGA0"].clip(gain); + +    //convert to attenuation +    double attn = wbx_rx_gain_ranges["PGA0"].stop() - gain; + +    //calculate the attenuation +    int attn_code = boost::math::iround(attn*2); +    int iobits = ((~attn_code) << RX_ATTN_SHIFT) & RX_ATTN_MASK; + +    UHD_LOGV(often) << boost::format( +        "WBX RX Attenuation: %f dB, Code: %d, IO Bits %x, Mask: %x" +    ) % attn % attn_code % (iobits & RX_ATTN_MASK) % RX_ATTN_MASK << std::endl; + +    //the actual gain setting +    gain = wbx_rx_gain_ranges["PGA0"].stop() - double(attn_code)/2; + +    return iobits; +} + + +/*********************************************************************** + * WBX Common Implementation + **********************************************************************/ +wbx_base::wbx_base(ctor_args_t args) : xcvr_dboard_base(args){ + +    //enable the clocks that we need +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_TX, true); +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_RX, true); + +    //////////////////////////////////////////////////////////////////// +    // Register RX properties +    //////////////////////////////////////////////////////////////////// +    this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&wbx_base::get_locked, this, dboard_iface::UNIT_RX)); +    BOOST_FOREACH(const std::string &name, wbx_rx_gain_ranges.keys()){ +        this->get_rx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&wbx_base::set_rx_gain, this, _1, name)) +            .set(wbx_rx_gain_ranges[name].start()); +        this->get_rx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(wbx_rx_gain_ranges[name]); +    } +    this->get_rx_subtree()->create<std::string>("connection").set("IQ"); +    this->get_rx_subtree()->create<bool>("enabled") +        .subscribe(boost::bind(&wbx_base::set_rx_enabled, this, _1)) +        .set(true); //start enabled +    this->get_rx_subtree()->create<bool>("use_lo_offset").set(false); +    this->get_rx_subtree()->create<double>("bandwidth/value").set(2*20.0e6); //20MHz low-pass, we want complex double-sided +    this->get_rx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(2*20.0e6, 2*20.0e6)); + +    //////////////////////////////////////////////////////////////////// +    // Register TX properties +    //////////////////////////////////////////////////////////////////// +    this->get_tx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&wbx_base::get_locked, this, dboard_iface::UNIT_TX)); +    this->get_tx_subtree()->create<std::string>("connection").set("IQ"); +    this->get_tx_subtree()->create<bool>("use_lo_offset").set(false); +    this->get_tx_subtree()->create<double>("bandwidth/value").set(2*20.0e6); //20MHz low-pass, we want complex double-sided +    this->get_tx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(freq_range_t(2*20.0e6, 2*20.0e6)); + +    // instantiate subclass foo +    switch(get_rx_id().to_uint16()) { +        case 0x053: +            db_actual = wbx_versionx_sptr(new wbx_version2(this)); +            return; +        case 0x057: +            db_actual = wbx_versionx_sptr(new wbx_version3(this)); +            return; +        case 0x063: +            db_actual = wbx_versionx_sptr(new wbx_version4(this)); +            return; +        default: +            /* We didn't recognize the version of the board... */ +            UHD_THROW_INVALID_CODE_PATH(); +    } + +} + + +wbx_base::~wbx_base(void){ +    /* NOP */ +} + +/*********************************************************************** + * Enables + **********************************************************************/ +void wbx_base::set_rx_enabled(bool enb){ +    this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, +        (enb)? RX_POWER_UP : RX_POWER_DOWN, RX_POWER_UP | RX_POWER_DOWN +    ); +} + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +double wbx_base::set_rx_gain(double gain, const std::string &name){ +    assert_has(wbx_rx_gain_ranges.keys(), name, "wbx rx gain name"); +    if(name == "PGA0"){ +        boost::uint16_t io_bits = rx_pga0_gain_to_iobits(gain); +        _rx_gains[name] = gain; + +        //write the new gain to rx gpio outputs +        this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, io_bits, RX_ATTN_MASK); +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    return _rx_gains[name]; //returned shadowed +} + +/*********************************************************************** + * Tuning + **********************************************************************/ +sensor_value_t wbx_base::get_locked(dboard_iface::unit_t unit){ +    const bool locked = (this->get_iface()->read_gpio(unit) & LOCKDET_MASK) != 0; +    return sensor_value_t("LO", locked, "locked", "unlocked"); +} diff --git a/host/lib/usrp/dboard/db_wbx_common.hpp b/host/lib/usrp/dboard/db_wbx_common.hpp new file mode 100644 index 000000000..9e984dce7 --- /dev/null +++ b/host/lib/usrp/dboard/db_wbx_common.hpp @@ -0,0 +1,204 @@ +// +// 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_DBOARD_DB_WBX_COMMON_HPP +#define INCLUDED_LIBUHD_USRP_DBOARD_DB_WBX_COMMON_HPP + +// Common IO Pins +#define ADF4350_CE      (1 << 3) +#define ADF4350_PDBRF   (1 << 2) +#define ADF4350_MUXOUT  (1 << 1)                // INPUT!!! +#define ADF4351_CE      (1 << 3) +#define ADF4351_PDBRF   (1 << 2) +#define ADF4351_MUXOUT  (1 << 1)                // INPUT!!! + +#define LOCKDET_MASK    (1 << 0)                // INPUT!!! + +// TX IO Pins +#define TX_PUP_5V       (1 << 7)                // enables 5.0V power supply +#define TX_PUP_3V       (1 << 6)                // enables 3.3V supply +#define TXMOD_EN        (1 << 4)                // on UNIT_TX, 1 enables TX Modulator + +// RX IO Pins +#define RX_PUP_5V       (1 << 7)                // enables 5.0V power supply +#define RX_PUP_3V       (1 << 6)                // enables 3.3V supply +#define RXBB_PDB        (1 << 4)                // on UNIT_RX, 1 powers up RX baseband + +// RX Attenuator Pins +#define RX_ATTN_SHIFT   8                       // lsb of RX Attenuator Control +#define RX_ATTN_MASK    (63 << RX_ATTN_SHIFT)      // valid bits of RX Attenuator Control + +// TX Attenuator Pins (v3 only) +#define TX_ATTN_16      (1 << 14) +#define TX_ATTN_8       (1 << 5) +#define TX_ATTN_4       (1 << 4) +#define TX_ATTN_2       (1 << 3) +#define TX_ATTN_1       (1 << 1) +#define TX_ATTN_MASK    (TX_ATTN_16|TX_ATTN_8|TX_ATTN_4|TX_ATTN_2|TX_ATTN_1)      // valid bits of TX Attenuator Control + +// Mixer functions +#define TX_MIXER_ENB    (TXMOD_EN|ADF4350_PDBRF)    // for v3, TXMOD_EN tied to ADF4350_PDBRF rather than separate +#define TX_MIXER_DIS    0 + +#define RX_MIXER_ENB    (RXBB_PDB|ADF4350_PDBRF) +#define RX_MIXER_DIS    0 + +// Power functions +#define TX_POWER_UP     (TX_PUP_5V|TX_PUP_3V) // high enables power supply +#define TX_POWER_DOWN   0 + +#define RX_POWER_UP     (RX_PUP_5V|RX_PUP_3V|ADF4350_CE) // high enables power supply +#define RX_POWER_DOWN   0 + + +#include <uhd/types/dict.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/utils/log.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/math/special_functions/round.hpp> +#include <boost/bind.hpp> + +namespace uhd{ namespace usrp{ + + +/*********************************************************************** + * The WBX Common dboard constants + **********************************************************************/ +static const uhd::dict<std::string, gain_range_t> wbx_rx_gain_ranges = boost::assign::map_list_of +    ("PGA0", gain_range_t(0, 31.5, 0.5)); + + +/*********************************************************************** + * The WBX dboard base class + **********************************************************************/ +class wbx_base : public xcvr_dboard_base{ +public: +    wbx_base(ctor_args_t args); +    virtual ~wbx_base(void); + +protected: +    virtual double set_rx_gain(double gain, const std::string &name); + +    virtual void set_rx_enabled(bool enb); + +    /*! +     * Get the lock detect status of the LO. +     * +     * This operation is identical for all versions of the WBX board. +     * \param unit which unit rx or tx +     * \return true for locked +     */ +    virtual sensor_value_t get_locked(dboard_iface::unit_t unit); + +    /*! +     * Version-agnostic ABC that wraps version-specific implementations of the +     * WBX base daughterboard. +     * +     * This class is an abstract base class, and thus is impossible to +     * instantiate. +     */ +    class wbx_versionx { +    public: +        wbx_versionx() {} +        ~wbx_versionx(void) {} + +        virtual double set_tx_gain(double gain, const std::string &name) = 0; +        virtual void set_tx_enabled(bool enb) = 0; +        virtual double set_lo_freq(dboard_iface::unit_t unit, double target_freq) = 0; + +        /*! This is the registered instance of the wrapper class, wbx_base. */ +        wbx_base *self_base; + +        property_tree::sptr get_rx_subtree(void){ +            return self_base->get_rx_subtree(); +        } + +        property_tree::sptr get_tx_subtree(void){ +            return self_base->get_tx_subtree(); +        } +    }; + + +    /*! +     * Version 2 of the WBX Daughterboard +     * +     * Basically the original release of the DB. +     */ +    class wbx_version2 : public wbx_versionx { +    public: +        wbx_version2(wbx_base *_self_wbx_base); +        ~wbx_version2(void); + +        double set_tx_gain(double gain, const std::string &name); +        void set_tx_enabled(bool enb); +        double set_lo_freq(dboard_iface::unit_t unit, double target_freq); +    }; + +    /*! +     * Version 3 of the WBX Daughterboard +     * +     * Fixed a problem with the AGC from Version 2. +     */ +    class wbx_version3 : public wbx_versionx { +    public: +        wbx_version3(wbx_base *_self_wbx_base); +        ~wbx_version3(void); + +        double set_tx_gain(double gain, const std::string &name); +        void set_tx_enabled(bool enb); +        double set_lo_freq(dboard_iface::unit_t unit, double target_freq); +    }; + +    /*! +     * Version 4 of the WBX Daughterboard +     * +     * Upgrades the Frequnecy Synthensizer from ADF4350 to ADF4351. +     */ +    class wbx_version4 : public wbx_versionx { +    public: +        wbx_version4(wbx_base *_self_wbx_base); +        ~wbx_version4(void); + +        double set_tx_gain(double gain, const std::string &name); +        void set_tx_enabled(bool enb); +        double set_lo_freq(dboard_iface::unit_t unit, double target_freq); +    }; + +    /*! +     * Handle to the version-specific implementation of the WBX. +     * +     * Since many of this class's functions are dependent on the version of the +     * WBX board, this class will instantiate an object of the appropriate +     * wbx_version_* subclass, and invoke any relevant functions through that +     * object.  This pointer is set to the proper object at construction time. +     */ +    typedef boost::shared_ptr<wbx_versionx> wbx_versionx_sptr; +    wbx_versionx_sptr db_actual; + +    uhd::dict<std::string, double> _tx_gains, _rx_gains; +    bool _rx_enabled, _tx_enabled; +}; + + +}} //namespace uhd::usrp + +#endif /* INCLUDED_LIBUHD_USRP_DBOARD_DB_WBX_COMMON_HPP */ diff --git a/host/lib/usrp/dboard/db_wbx_simple.cpp b/host/lib/usrp/dboard/db_wbx_simple.cpp new file mode 100644 index 000000000..4ba30255d --- /dev/null +++ b/host/lib/usrp/dboard/db_wbx_simple.cpp @@ -0,0 +1,162 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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/>. +// + +// Antenna constants +#define ANTSW_IO        ((1 << 15))             // on UNIT_TX, 0 = TX, 1 = RX, on UNIT_RX 0 = main ant, 1 = RX2 +#define ANT_TX          0                       //the tx line is transmitting +#define ANT_RX          ANTSW_IO                //the tx line is receiving +#define ANT_TXRX        0                       //the rx line is on txrx +#define ANT_RX2         ANTSW_IO                //the rx line in on rx2 + +#include "db_wbx_common.hpp" +#include <uhd/utils/static.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <boost/assign/list_of.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + + +/*********************************************************************** + * The WBX Simple dboard constants + **********************************************************************/ +static const std::vector<std::string> wbx_tx_antennas = list_of("TX/RX")("CAL"); + +static const std::vector<std::string> wbx_rx_antennas = list_of("TX/RX")("RX2")("CAL"); + +/*********************************************************************** + * The WBX simple implementation + **********************************************************************/ +class wbx_simple : public wbx_base{ +public: +    wbx_simple(ctor_args_t args); +    ~wbx_simple(void); + +private: +    void set_rx_ant(const std::string &ant); +    void set_tx_ant(const std::string &ant); +    std::string _rx_ant; +}; + +/*********************************************************************** + * Register the WBX simple implementation + **********************************************************************/ +static dboard_base::sptr make_wbx_simple(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new wbx_simple(args)); +} + +/*********************************************************************** + * ID Numbers for WBX daughterboard combinations. + **********************************************************************/ +UHD_STATIC_BLOCK(reg_wbx_simple_dboards){ +    dboard_manager::register_dboard(0x0053, 0x0052, &make_wbx_simple, "WBX"); +    dboard_manager::register_dboard(0x0053, 0x004f, &make_wbx_simple, "WBX + Simple GDB"); +    dboard_manager::register_dboard(0x0057, 0x0056, &make_wbx_simple, "WBX v3"); +    dboard_manager::register_dboard(0x0057, 0x004f, &make_wbx_simple, "WBX v3 + Simple GDB"); +    dboard_manager::register_dboard(0x0063, 0x0062, &make_wbx_simple, "WBX v4"); +    dboard_manager::register_dboard(0x0063, 0x004f, &make_wbx_simple, "WBX v4 + Simple GDB"); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +wbx_simple::wbx_simple(ctor_args_t args) : wbx_base(args){ + +    //////////////////////////////////////////////////////////////////// +    // Register RX properties +    //////////////////////////////////////////////////////////////////// + +    this->get_rx_subtree()->access<std::string>("name").set( +        std::string(str(boost::format("%s+GDB") % this->get_rx_subtree()->access<std::string>("name").get() +    ))); +    this->get_rx_subtree()->create<std::string>("antenna/value") +        .subscribe(boost::bind(&wbx_simple::set_rx_ant, this, _1)) +        .set("RX2"); +    this->get_rx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(wbx_rx_antennas); + +    //////////////////////////////////////////////////////////////////// +    // Register TX properties +    //////////////////////////////////////////////////////////////////// +    this->get_tx_subtree()->access<std::string>("name").set( +        std::string(str(boost::format("%s+GDB") % this->get_tx_subtree()->access<std::string>("name").get() +    ))); +    this->get_tx_subtree()->create<std::string>("antenna/value") +        .subscribe(boost::bind(&wbx_simple::set_tx_ant, this, _1)) +        .set(wbx_tx_antennas.at(0)); +    this->get_tx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(wbx_tx_antennas); + +    //set the gpio directions and atr controls (antenna switches all under ATR) +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_TX, ANTSW_IO, ANTSW_IO); +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, ANTSW_IO, ANTSW_IO); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_TX, ANTSW_IO, ANTSW_IO); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, ANTSW_IO, ANTSW_IO); + +    //setup ATR for the antenna switches (constant) +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_IDLE,        ANT_RX, ANTSW_IO); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_RX_ONLY,     ANT_RX, ANTSW_IO); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     ANT_TX, ANTSW_IO); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, ANT_TX, ANTSW_IO); + +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_IDLE,        ANT_TXRX, ANTSW_IO); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_TX_ONLY,     ANT_RX2, ANTSW_IO); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_FULL_DUPLEX, ANT_RX2, ANTSW_IO); +} + +wbx_simple::~wbx_simple(void){ +    /* NOP */ +} + +/*********************************************************************** + * Antennas + **********************************************************************/ +void wbx_simple::set_rx_ant(const std::string &ant){ +    //validate input +    assert_has(wbx_rx_antennas, ant, "wbx rx antenna name"); + +    //shadow the setting +    _rx_ant = ant; + +    //write the new antenna setting to atr regs +    if (_rx_ant == "CAL") { +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_TX_ONLY,     ANT_TXRX, ANTSW_IO); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_FULL_DUPLEX, ANT_TXRX, ANTSW_IO); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_RX_ONLY,     ANT_TXRX, ANTSW_IO); +    }  +    else { +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_TX_ONLY,     ANT_RX2, ANTSW_IO); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_FULL_DUPLEX, ANT_RX2, ANTSW_IO); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_RX_ONLY, ((_rx_ant == "TX/RX")? ANT_TXRX : ANT_RX2), ANTSW_IO); +    } +} + +void wbx_simple::set_tx_ant(const std::string &ant){ +    assert_has(wbx_tx_antennas, ant, "wbx tx antenna name"); + +    //write the new antenna setting to atr regs +    if (ant == "CAL") { +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     ANT_RX, ANTSW_IO); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, ANT_RX, ANTSW_IO); +    }  +    else { +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     ANT_TX, ANTSW_IO); +        this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, ANT_TX, ANTSW_IO); +    } +} diff --git a/host/lib/usrp/dboard/db_wbx_version2.cpp b/host/lib/usrp/dboard/db_wbx_version2.cpp new file mode 100644 index 000000000..643fcd37f --- /dev/null +++ b/host/lib/usrp/dboard/db_wbx_version2.cpp @@ -0,0 +1,338 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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 "db_wbx_common.hpp" +#include "adf4350_regs.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/math/special_functions/round.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + + +/*********************************************************************** + * WBX Version 2 Constants + **********************************************************************/ +static const uhd::dict<std::string, gain_range_t> wbx_v2_tx_gain_ranges = map_list_of +    ("PGA0", gain_range_t(0, 25, 0.05)) +; + +static const freq_range_t wbx_v2_freq_range(68.75e6, 2.2e9); + +/*********************************************************************** + * Gain-related functions + **********************************************************************/ +static double tx_pga0_gain_to_dac_volts(double &gain){ +    //clip the input +    gain = wbx_v2_tx_gain_ranges["PGA0"].clip(gain); + +    //voltage level constants +    static const double max_volts = 0.5, min_volts = 1.4; +    static const double slope = (max_volts-min_volts)/wbx_v2_tx_gain_ranges["PGA0"].stop(); + +    //calculate the voltage for the aux dac +    double dac_volts = gain*slope + min_volts; + +    UHD_LOGV(often) << boost::format( +        "WBX TX Gain: %f dB, dac_volts: %f V" +    ) % gain % dac_volts << std::endl; + +    //the actual gain setting +    gain = (dac_volts - min_volts)/slope; + +    return dac_volts; +} + + +/*********************************************************************** + * WBX Version 2 Implementation + **********************************************************************/ +wbx_base::wbx_version2::wbx_version2(wbx_base *_self_wbx_base) { +    //register our handle on the primary wbx_base instance +    self_base = _self_wbx_base; + +    //////////////////////////////////////////////////////////////////// +    // Register RX properties +    //////////////////////////////////////////////////////////////////// +    this->get_rx_subtree()->create<std::string>("name").set("WBXv2 RX"); +    this->get_rx_subtree()->create<double>("freq/value") +         .coerce(boost::bind(&wbx_base::wbx_version2::set_lo_freq, this, dboard_iface::UNIT_RX, _1)) +         .set((wbx_v2_freq_range.start() + wbx_v2_freq_range.stop())/2.0); +    this->get_rx_subtree()->create<meta_range_t>("freq/range").set(wbx_v2_freq_range); + +    //////////////////////////////////////////////////////////////////// +    // Register TX properties +    //////////////////////////////////////////////////////////////////// +    this->get_tx_subtree()->create<std::string>("name").set("WBXv2 TX"); +    BOOST_FOREACH(const std::string &name, wbx_v2_tx_gain_ranges.keys()){ +        self_base->get_tx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&wbx_base::wbx_version2::set_tx_gain, this, _1, name)) +            .set(wbx_v2_tx_gain_ranges[name].start()); +        self_base->get_tx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(wbx_v2_tx_gain_ranges[name]); +    } +    this->get_tx_subtree()->create<double>("freq/value") +         .coerce(boost::bind(&wbx_base::wbx_version2::set_lo_freq, this, dboard_iface::UNIT_TX, _1)) +         .set((wbx_v2_freq_range.start() + wbx_v2_freq_range.stop())/2.0); +    this->get_tx_subtree()->create<meta_range_t>("freq/range").set(wbx_v2_freq_range); +    this->get_tx_subtree()->create<bool>("enabled") +        .subscribe(boost::bind(&wbx_base::wbx_version2::set_tx_enabled, this, _1)) +        .set(true); //start enabled + +    //set attenuator control bits +    int v2_iobits = ADF4350_CE; +    int v2_tx_mod = TXMOD_EN|ADF4350_PDBRF; + +    //set the gpio directions and atr controls +    self_base->get_iface()->set_pin_ctrl(dboard_iface::UNIT_TX, v2_tx_mod); +    self_base->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, RXBB_PDB|ADF4350_PDBRF); +    self_base->get_iface()->set_gpio_ddr(dboard_iface::UNIT_TX, TX_PUP_5V|TX_PUP_3V|v2_tx_mod|v2_iobits); +    self_base->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, RX_PUP_5V|RX_PUP_3V|ADF4350_CE|RXBB_PDB|ADF4350_PDBRF|RX_ATTN_MASK); + +    //setup ATR for the mixer enables (always enabled to prevent phase slip between bursts) +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_IDLE,        v2_tx_mod, TX_MIXER_DIS | v2_tx_mod); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_RX_ONLY,     v2_tx_mod, TX_MIXER_DIS | v2_tx_mod); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     v2_tx_mod, TX_MIXER_DIS | v2_tx_mod); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, v2_tx_mod, TX_MIXER_DIS | v2_tx_mod); + +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_IDLE,        RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_TX_ONLY,     RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_RX_ONLY,     RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_FULL_DUPLEX, RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +} + +wbx_base::wbx_version2::~wbx_version2(void){ +    /* NOP */ +} + +/*********************************************************************** + * Enables + **********************************************************************/ +void wbx_base::wbx_version2::set_tx_enabled(bool enb){ +    self_base->get_iface()->set_gpio_out(dboard_iface::UNIT_TX, +        (enb)? TX_POWER_UP | ADF4350_CE : TX_POWER_DOWN, TX_POWER_UP | TX_POWER_DOWN | ADF4350_CE); +} + + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +double wbx_base::wbx_version2::set_tx_gain(double gain, const std::string &name){ +    assert_has(wbx_v2_tx_gain_ranges.keys(), name, "wbx tx gain name"); +    if(name == "PGA0"){ +        double dac_volts = tx_pga0_gain_to_dac_volts(gain); +        self_base->_tx_gains[name] = gain; + +        //write the new voltage to the aux dac +        self_base->get_iface()->write_aux_dac(dboard_iface::UNIT_TX, dboard_iface::AUX_DAC_A, dac_volts); +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    return self_base->_tx_gains[name]; //shadowed +} + + +/*********************************************************************** + * Tuning + **********************************************************************/ +double wbx_base::wbx_version2::set_lo_freq(dboard_iface::unit_t unit, double target_freq) { +    //clip to tuning range +    target_freq = wbx_v2_freq_range.clip(target_freq); + +    UHD_LOGV(often) << boost::format( +        "WBX tune: target frequency %f Mhz" +    ) % (target_freq/1e6) << std::endl; + +    //start with target_freq*2 because mixer has divide by 2 +    target_freq *= 2; + +    //map prescaler setting to mininmum integer divider (N) values (pg.18 prescaler) +    static const uhd::dict<int, int> prescaler_to_min_int_div = map_list_of +        (0,23) //adf4350_regs_t::PRESCALER_4_5 +        (1,75) //adf4350_regs_t::PRESCALER_8_9 +    ; + +    //map rf divider select output dividers to enums +    static const uhd::dict<int, adf4350_regs_t::rf_divider_select_t> rfdivsel_to_enum = map_list_of +        (1,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV1) +        (2,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV2) +        (4,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV4) +        (8,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV8) +        (16, adf4350_regs_t::RF_DIVIDER_SELECT_DIV16) +    ; + +    double actual_freq, pfd_freq; +    double ref_freq = self_base->get_iface()->get_clock_rate(unit); +    int R=0, BS=0, N=0, FRAC=0, MOD=0; +    int RFdiv = 1; +    adf4350_regs_t::reference_divide_by_2_t T     = adf4350_regs_t::REFERENCE_DIVIDE_BY_2_DISABLED; +    adf4350_regs_t::reference_doubler_t     D     = adf4350_regs_t::REFERENCE_DOUBLER_DISABLED;     + +    //Reference doubler for 50% duty cycle +    // if ref_freq < 12.5MHz enable regs.reference_divide_by_2 +    if(ref_freq <= 12.5e6) D = adf4350_regs_t::REFERENCE_DOUBLER_ENABLED; + +    //increase RF divider until acceptable VCO frequency +    const bool do_sync = (target_freq/2 > ref_freq); +    double vco_freq = target_freq; +    while (vco_freq < 2.2e9) { +        vco_freq *= 2; +        RFdiv *= 2; +    } +    if (do_sync) vco_freq = target_freq; + +    //use 8/9 prescaler for vco_freq > 3 GHz (pg.18 prescaler) +    adf4350_regs_t::prescaler_t prescaler = vco_freq > 3e9 ? adf4350_regs_t::PRESCALER_8_9 : adf4350_regs_t::PRESCALER_4_5; + +    /* +     * The goal here is to loop though possible R dividers, +     * band select clock dividers, N (int) dividers, and FRAC  +     * (frac) dividers. +     * +     * Calculate the N and F dividers for each set of values. +     * The loop exits when it meets all of the constraints. +     * The resulting loop values are loaded into the registers. +     * +     * from pg.21 +     * +     * f_pfd = f_ref*(1+D)/(R*(1+T)) +     * f_vco = (N + (FRAC/MOD))*f_pfd +     *    N = f_vco/f_pfd - FRAC/MOD = f_vco*((R*(T+1))/(f_ref*(1+D))) - FRAC/MOD +     * f_rf = f_vco/RFdiv) +     * f_actual = f_rf/2 +     */ +    for(R = 1; R <= 1023; R+=1){ +        //PFD input frequency = f_ref/R ... ignoring Reference doubler/divide-by-2 (D & T) +        pfd_freq = ref_freq*(1+D)/(R*(1+T)); + +        //keep the PFD frequency at or below 25MHz (Loop Filter Bandwidth) +        if (pfd_freq > 25e6) continue; + +        //ignore fractional part of tuning +        N = int(std::floor(vco_freq/pfd_freq)); + +        //keep N > minimum int divider requirement +        if (N < prescaler_to_min_int_div[prescaler]) continue; + +        for(BS=1; BS <= 255; BS+=1){ +            //keep the band select frequency at or below 100KHz +            //constraint on band select clock +            if (pfd_freq/BS > 100e3) continue; +            goto done_loop; +        } +    } done_loop: + +    //Fractional-N calculation +    MOD = 4095; //max fractional accuracy +    FRAC = int((vco_freq/pfd_freq - N)*MOD); + +    //Reference divide-by-2 for 50% duty cycle +    // if R even, move one divide by 2 to to regs.reference_divide_by_2 +    if(R % 2 == 0){ +        T = adf4350_regs_t::REFERENCE_DIVIDE_BY_2_ENABLED; +        R /= 2; +    } + +    //actual frequency calculation +    actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))/2/(vco_freq/target_freq)); + +    UHD_LOGV(often) +        << boost::format("WBX Intermediates: ref=%0.2f, outdiv=%f, fbdiv=%f") % (ref_freq*(1+int(D))/(R*(1+int(T)))) % double(RFdiv*2) % double(N + double(FRAC)/double(MOD)) << std::endl + +        << boost::format("WBX tune: R=%d, BS=%d, N=%d, FRAC=%d, MOD=%d, T=%d, D=%d, RFdiv=%d" +            ) % R % BS % N % FRAC % MOD % T % D % RFdiv << std::endl +        << boost::format("WBX Frequencies (MHz): REQ=%0.2f, ACT=%0.2f, VCO=%0.2f, PFD=%0.2f, BAND=%0.2f" +            ) % (target_freq/1e6) % (actual_freq/1e6) % (vco_freq/1e6) % (pfd_freq/1e6) % (pfd_freq/BS/1e6) << std::endl; + +    //load the register values +    adf4350_regs_t regs; + +    regs.frac_12_bit = FRAC; +    regs.int_16_bit = N; +    regs.mod_12_bit = MOD; +    if (do_sync) +    { +        regs.clock_divider_12_bit = std::max(1, int(std::ceil(400e-6*pfd_freq/MOD))); +        regs.feedback_select = adf4350_regs_t::FEEDBACK_SELECT_DIVIDED; +        regs.clock_div_mode = adf4350_regs_t::CLOCK_DIV_MODE_RESYNC_ENABLE; +    } +    regs.prescaler = prescaler; +    regs.r_counter_10_bit = R; +    regs.reference_divide_by_2 = T; +    regs.reference_doubler = D; +    regs.band_select_clock_div = BS; +    UHD_ASSERT_THROW(rfdivsel_to_enum.has_key(RFdiv)); +    regs.rf_divider_select = rfdivsel_to_enum[RFdiv]; + +    if (unit == dboard_iface::UNIT_RX) { +        freq_range_t rx_lo_5dbm = list_of +            (range_t(0.05e9, 1.4e9)) +        ; + +        freq_range_t rx_lo_2dbm = list_of +            (range_t(1.4e9, 2.2e9)) +        ; + +        if (actual_freq == rx_lo_5dbm.clip(actual_freq)) regs.output_power = adf4350_regs_t::OUTPUT_POWER_5DBM; + +        if (actual_freq == rx_lo_2dbm.clip(actual_freq)) regs.output_power = adf4350_regs_t::OUTPUT_POWER_2DBM; + +    } else if (unit == dboard_iface::UNIT_TX) { +        freq_range_t tx_lo_5dbm = list_of +            (range_t(0.05e9, 1.7e9)) +            (range_t(1.9e9, 2.2e9)) +        ; + +        freq_range_t tx_lo_m1dbm = list_of +            (range_t(1.7e9, 1.9e9)) +        ; + +        if (actual_freq == tx_lo_5dbm.clip(actual_freq)) regs.output_power = adf4350_regs_t::OUTPUT_POWER_5DBM; + +        if (actual_freq == tx_lo_m1dbm.clip(actual_freq)) regs.output_power = adf4350_regs_t::OUTPUT_POWER_M1DBM; + +    } + +    //write the registers +    //correct power-up sequence to write registers (5, 4, 3, 2, 1, 0) +    int addr; + +    for(addr=5; addr>=0; addr--){ +        UHD_LOGV(often) << boost::format( +            "WBX SPI Reg (0x%02x): 0x%08x" +        ) % addr % regs.get_reg(addr) << std::endl; +        self_base->get_iface()->write_spi( +            unit, spi_config_t::EDGE_RISE, +            regs.get_reg(addr), 32 +        ); +    } + +    //return the actual frequency +    UHD_LOGV(often) << boost::format( +        "WBX tune: actual frequency %f Mhz" +    ) % (actual_freq/1e6) << std::endl; +    return actual_freq; +} diff --git a/host/lib/usrp/dboard/db_wbx_version3.cpp b/host/lib/usrp/dboard/db_wbx_version3.cpp new file mode 100644 index 000000000..6771d184f --- /dev/null +++ b/host/lib/usrp/dboard/db_wbx_version3.cpp @@ -0,0 +1,370 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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 "db_wbx_common.hpp" +#include "adf4350_regs.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/math/special_functions/round.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + + +/*********************************************************************** + * WBX Version 3 Constants + **********************************************************************/ +static const uhd::dict<std::string, gain_range_t> wbx_v3_tx_gain_ranges = map_list_of +    ("PGA0", gain_range_t(0, 31, 1.0)) +; + +static const freq_range_t wbx_v3_freq_range(68.75e6, 2.2e9); + +/*********************************************************************** + * Gain-related functions + **********************************************************************/ +static int tx_pga0_gain_to_iobits(double &gain){ +    //clip the input +    gain = wbx_v3_tx_gain_ranges["PGA0"].clip(gain); + +    //convert to attenuation +    double attn = wbx_v3_tx_gain_ranges["PGA0"].stop() - gain; + +    //calculate the attenuation +    int attn_code = boost::math::iround(attn); +    int iobits = ( +            (attn_code & 16 ? 0 : TX_ATTN_16) | +            (attn_code &  8 ? 0 : TX_ATTN_8) | +            (attn_code &  4 ? 0 : TX_ATTN_4) | +            (attn_code &  2 ? 0 : TX_ATTN_2) | +            (attn_code &  1 ? 0 : TX_ATTN_1)  +        ) & TX_ATTN_MASK; + +    UHD_LOGV(often) << boost::format( +        "WBX TX Attenuation: %f dB, Code: %d, IO Bits %x, Mask: %x" +    ) % attn % attn_code % (iobits & TX_ATTN_MASK) % TX_ATTN_MASK << std::endl; + +    //the actual gain setting +    gain = wbx_v3_tx_gain_ranges["PGA0"].stop() - double(attn_code); + +    return iobits; +} + + +/*********************************************************************** + * WBX Common Implementation + **********************************************************************/ +wbx_base::wbx_version3::wbx_version3(wbx_base *_self_wbx_base) { +    //register our handle on the primary wbx_base instance +    self_base = _self_wbx_base; + +    //////////////////////////////////////////////////////////////////// +    // Register RX properties +    //////////////////////////////////////////////////////////////////// +    this->get_rx_subtree()->create<std::string>("name").set("WBXv3 RX"); +    this->get_rx_subtree()->create<double>("freq/value") +         .coerce(boost::bind(&wbx_base::wbx_version3::set_lo_freq, this, dboard_iface::UNIT_RX, _1)) +         .set((wbx_v3_freq_range.start() + wbx_v3_freq_range.stop())/2.0); +    this->get_rx_subtree()->create<meta_range_t>("freq/range").set(wbx_v3_freq_range); + +    //////////////////////////////////////////////////////////////////// +    // Register TX properties +    //////////////////////////////////////////////////////////////////// +    this->get_tx_subtree()->create<std::string>("name").set("WBXv3 TX"); +    BOOST_FOREACH(const std::string &name, wbx_v3_tx_gain_ranges.keys()){ +        self_base->get_tx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&wbx_base::wbx_version3::set_tx_gain, this, _1, name)) +            .set(wbx_v3_tx_gain_ranges[name].start()); +        self_base->get_tx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(wbx_v3_tx_gain_ranges[name]); +    } +    this->get_tx_subtree()->create<double>("freq/value") +         .coerce(boost::bind(&wbx_base::wbx_version3::set_lo_freq, this, dboard_iface::UNIT_TX, _1)) +         .set((wbx_v3_freq_range.start() + wbx_v3_freq_range.stop())/2.0); +    this->get_tx_subtree()->create<meta_range_t>("freq/range").set(wbx_v3_freq_range); +    this->get_tx_subtree()->create<bool>("enabled") +        .subscribe(boost::bind(&wbx_base::wbx_version3::set_tx_enabled, this, _1)) +        .set(true); //start enabled + +    //set attenuator control bits +    int v3_iobits = TX_ATTN_MASK; +    int v3_tx_mod = ADF4350_PDBRF; + +    //set the gpio directions and atr controls +    self_base->get_iface()->set_pin_ctrl(dboard_iface::UNIT_TX, \ +            v3_tx_mod|v3_iobits); +    self_base->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, \ +            RXBB_PDB|ADF4350_PDBRF); +    self_base->get_iface()->set_gpio_ddr(dboard_iface::UNIT_TX, \ +            TX_PUP_5V|TX_PUP_3V|v3_tx_mod|v3_iobits); +    self_base->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, \ +            RX_PUP_5V|RX_PUP_3V|ADF4350_CE|RXBB_PDB|ADF4350_PDBRF|RX_ATTN_MASK); + +    //setup ATR for the mixer enables (always enabled to prevent phase +    //slip between bursts).  set TX gain iobits to min gain (max attenuation) +    //when RX_ONLY or IDLE to suppress LO leakage +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, \ +            dboard_iface::ATR_REG_IDLE, v3_tx_mod, \ +            TX_ATTN_MASK | TX_MIXER_DIS | v3_tx_mod); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, \ +            dboard_iface::ATR_REG_RX_ONLY, v3_tx_mod, \ +            TX_ATTN_MASK | TX_MIXER_DIS | v3_tx_mod); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, \ +            dboard_iface::ATR_REG_TX_ONLY, v3_tx_mod, \ +            TX_ATTN_MASK | TX_MIXER_DIS | v3_tx_mod); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, \ +            dboard_iface::ATR_REG_FULL_DUPLEX, v3_tx_mod, \ +            TX_ATTN_MASK | TX_MIXER_DIS | v3_tx_mod); + +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, \ +            dboard_iface::ATR_REG_IDLE, \ +            RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, \ +            dboard_iface::ATR_REG_TX_ONLY, \ +            RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, \ +            dboard_iface::ATR_REG_RX_ONLY, \ +            RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, \ +            dboard_iface::ATR_REG_FULL_DUPLEX, \ +            RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +} + +wbx_base::wbx_version3::~wbx_version3(void){ +    /* NOP */ +} + + +/*********************************************************************** + * Enables + **********************************************************************/ +void wbx_base::wbx_version3::set_tx_enabled(bool enb){ +    self_base->get_iface()->set_gpio_out(dboard_iface::UNIT_TX, +        (enb)? TX_POWER_UP | ADF4350_CE : TX_POWER_DOWN, TX_POWER_UP | TX_POWER_DOWN | 0); +} + + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +double wbx_base::wbx_version3::set_tx_gain(double gain, const std::string &name){ +    assert_has(wbx_v3_tx_gain_ranges.keys(), name, "wbx tx gain name"); +    if(name == "PGA0"){ +        boost::uint16_t io_bits = tx_pga0_gain_to_iobits(gain); + +        self_base->_tx_gains[name] = gain; + +        //write the new gain to tx gpio outputs +        //Update ATR with gain io_bits, only update for TX_ONLY and FULL_DUPLEX ATR states +        self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     io_bits, TX_ATTN_MASK); +        self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, io_bits, TX_ATTN_MASK); +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    return self_base->_tx_gains[name]; //shadow +} + + +/*********************************************************************** + * Tuning + **********************************************************************/ +double wbx_base::wbx_version3::set_lo_freq(dboard_iface::unit_t unit, double target_freq) { +    //clip to tuning range +    target_freq = wbx_v3_freq_range.clip(target_freq); + +    UHD_LOGV(often) << boost::format( +        "WBX tune: target frequency %f Mhz" +    ) % (target_freq/1e6) << std::endl; + +    //start with target_freq*2 because mixer has divide by 2 +    target_freq *= 2; + +    //map prescaler setting to mininmum integer divider (N) values (pg.18 prescaler) +    static const uhd::dict<int, int> prescaler_to_min_int_div = map_list_of +        (0,23) //adf4350_regs_t::PRESCALER_4_5 +        (1,75) //adf4350_regs_t::PRESCALER_8_9 +    ; + +    //map rf divider select output dividers to enums +    static const uhd::dict<int, adf4350_regs_t::rf_divider_select_t> rfdivsel_to_enum = map_list_of +        (1,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV1) +        (2,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV2) +        (4,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV4) +        (8,  adf4350_regs_t::RF_DIVIDER_SELECT_DIV8) +        (16, adf4350_regs_t::RF_DIVIDER_SELECT_DIV16) +    ; + +    double actual_freq, pfd_freq; +    double ref_freq = self_base->get_iface()->get_clock_rate(unit); +    int R=0, BS=0, N=0, FRAC=0, MOD=0; +    int RFdiv = 1; +    adf4350_regs_t::reference_divide_by_2_t T     = adf4350_regs_t::REFERENCE_DIVIDE_BY_2_DISABLED; +    adf4350_regs_t::reference_doubler_t     D     = adf4350_regs_t::REFERENCE_DOUBLER_DISABLED;     + +    //Reference doubler for 50% duty cycle +    // if ref_freq < 12.5MHz enable regs.reference_divide_by_2 +    if(ref_freq <= 12.5e6) D = adf4350_regs_t::REFERENCE_DOUBLER_ENABLED; + +    //increase RF divider until acceptable VCO frequency +    const bool do_sync = (target_freq/2 > ref_freq); +    double vco_freq = target_freq; +    while (vco_freq < 2.2e9) { +        vco_freq *= 2; +        RFdiv *= 2; +    } +    if (do_sync) vco_freq = target_freq; + +    //use 8/9 prescaler for vco_freq > 3 GHz (pg.18 prescaler) +    adf4350_regs_t::prescaler_t prescaler = vco_freq > 3e9 ? adf4350_regs_t::PRESCALER_8_9 : adf4350_regs_t::PRESCALER_4_5; + +    /* +     * The goal here is to loop though possible R dividers, +     * band select clock dividers, N (int) dividers, and FRAC  +     * (frac) dividers. +     * +     * Calculate the N and F dividers for each set of values. +     * The loop exits when it meets all of the constraints. +     * The resulting loop values are loaded into the registers. +     * +     * from pg.21 +     * +     * f_pfd = f_ref*(1+D)/(R*(1+T)) +     * f_vco = (N + (FRAC/MOD))*f_pfd +     *    N = f_vco/f_pfd - FRAC/MOD = f_vco*((R*(T+1))/(f_ref*(1+D))) - FRAC/MOD +     * f_rf = f_vco/RFdiv) +     * f_actual = f_rf/2 +     */ +    for(R = 1; R <= 1023; R+=1){ +        //PFD input frequency = f_ref/R ... ignoring Reference doubler/divide-by-2 (D & T) +        pfd_freq = ref_freq*(1+D)/(R*(1+T)); + +        //keep the PFD frequency at or below 25MHz (Loop Filter Bandwidth) +        if (pfd_freq > 25e6) continue; + +        //ignore fractional part of tuning +        N = int(std::floor(vco_freq/pfd_freq)); + +        //keep N > minimum int divider requirement +        if (N < prescaler_to_min_int_div[prescaler]) continue; + +        for(BS=1; BS <= 255; BS+=1){ +            //keep the band select frequency at or below 100KHz +            //constraint on band select clock +            if (pfd_freq/BS > 100e3) continue; +            goto done_loop; +        } +    } done_loop: + +    //Fractional-N calculation +    MOD = 4095; //max fractional accuracy +    FRAC = int((vco_freq/pfd_freq - N)*MOD); + +    //Reference divide-by-2 for 50% duty cycle +    // if R even, move one divide by 2 to to regs.reference_divide_by_2 +    if(R % 2 == 0){ +        T = adf4350_regs_t::REFERENCE_DIVIDE_BY_2_ENABLED; +        R /= 2; +    } + +    //actual frequency calculation +    actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))/2/(vco_freq/target_freq)); + +    UHD_LOGV(often) +        << boost::format("WBX Intermediates: ref=%0.2f, outdiv=%f, fbdiv=%f") % (ref_freq*(1+int(D))/(R*(1+int(T)))) % double(RFdiv*2) % double(N + double(FRAC)/double(MOD)) << std::endl + +        << boost::format("WBX tune: R=%d, BS=%d, N=%d, FRAC=%d, MOD=%d, T=%d, D=%d, RFdiv=%d" +            ) % R % BS % N % FRAC % MOD % T % D % RFdiv << std::endl +        << boost::format("WBX Frequencies (MHz): REQ=%0.2f, ACT=%0.2f, VCO=%0.2f, PFD=%0.2f, BAND=%0.2f" +            ) % (target_freq/1e6) % (actual_freq/1e6) % (vco_freq/1e6) % (pfd_freq/1e6) % (pfd_freq/BS/1e6) << std::endl; + +    //load the register values +    adf4350_regs_t regs; + +    regs.frac_12_bit = FRAC; +    regs.int_16_bit = N; +    regs.mod_12_bit = MOD; +    if (do_sync) +    { +        regs.clock_divider_12_bit = std::max(1, int(std::ceil(400e-6*pfd_freq/MOD))); +        regs.feedback_select = adf4350_regs_t::FEEDBACK_SELECT_DIVIDED; +        regs.clock_div_mode = adf4350_regs_t::CLOCK_DIV_MODE_RESYNC_ENABLE; +    } +    regs.prescaler = prescaler; +    regs.r_counter_10_bit = R; +    regs.reference_divide_by_2 = T; +    regs.reference_doubler = D; +    regs.band_select_clock_div = BS; +    UHD_ASSERT_THROW(rfdivsel_to_enum.has_key(RFdiv)); +    regs.rf_divider_select = rfdivsel_to_enum[RFdiv]; + +    if (unit == dboard_iface::UNIT_RX) { +        freq_range_t rx_lo_5dbm = list_of +            (range_t(0.05e9, 1.4e9)) +        ; + +        freq_range_t rx_lo_2dbm = list_of +            (range_t(1.4e9, 2.2e9)) +        ; + +        if (actual_freq == rx_lo_5dbm.clip(actual_freq)) regs.output_power = adf4350_regs_t::OUTPUT_POWER_5DBM; + +        if (actual_freq == rx_lo_2dbm.clip(actual_freq)) regs.output_power = adf4350_regs_t::OUTPUT_POWER_2DBM; + +    } else if (unit == dboard_iface::UNIT_TX) { +        freq_range_t tx_lo_5dbm = list_of +            (range_t(0.05e9, 1.7e9)) +            (range_t(1.9e9, 2.2e9)) +        ; + +        freq_range_t tx_lo_m1dbm = list_of +            (range_t(1.7e9, 1.9e9)) +        ; + +        if (actual_freq == tx_lo_5dbm.clip(actual_freq)) regs.output_power = adf4350_regs_t::OUTPUT_POWER_5DBM; + +        if (actual_freq == tx_lo_m1dbm.clip(actual_freq)) regs.output_power = adf4350_regs_t::OUTPUT_POWER_M1DBM; + +    } + +    //write the registers +    //correct power-up sequence to write registers (5, 4, 3, 2, 1, 0) +    int addr; + +    for(addr=5; addr>=0; addr--){ +        UHD_LOGV(often) << boost::format( +            "WBX SPI Reg (0x%02x): 0x%08x" +        ) % addr % regs.get_reg(addr) << std::endl; +        self_base->get_iface()->write_spi( +            unit, spi_config_t::EDGE_RISE, +            regs.get_reg(addr), 32 +        ); +    } + +    //return the actual frequency +    UHD_LOGV(often) << boost::format( +        "WBX tune: actual frequency %f Mhz" +    ) % (actual_freq/1e6) << std::endl; +    return actual_freq; +} diff --git a/host/lib/usrp/dboard/db_wbx_version4.cpp b/host/lib/usrp/dboard/db_wbx_version4.cpp new file mode 100644 index 000000000..057cdb6ce --- /dev/null +++ b/host/lib/usrp/dboard/db_wbx_version4.cpp @@ -0,0 +1,353 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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 "db_wbx_common.hpp" +#include "adf4351_regs.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/math/special_functions/round.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + + +/*********************************************************************** + * WBX Version 3 Constants + **********************************************************************/ +static const uhd::dict<std::string, gain_range_t> wbx_v4_tx_gain_ranges = map_list_of +    ("PGA0", gain_range_t(0, 31, 1.0)) +; + +static const freq_range_t wbx_v4_freq_range(50.0e6, 2.2e9); + + +/*********************************************************************** + * Gain-related functions + **********************************************************************/ +static int tx_pga0_gain_to_iobits(double &gain){ +    //clip the input +    gain = wbx_v4_tx_gain_ranges["PGA0"].clip(gain); + +    //convert to attenuation +    double attn = wbx_v4_tx_gain_ranges["PGA0"].stop() - gain; + +    //calculate the attenuation +    int attn_code = boost::math::iround(attn); +    int iobits = ( +            (attn_code & 16 ? 0 : TX_ATTN_16) | +            (attn_code &  8 ? 0 : TX_ATTN_8) | +            (attn_code &  4 ? 0 : TX_ATTN_4) | +            (attn_code &  2 ? 0 : TX_ATTN_2) | +            (attn_code &  1 ? 0 : TX_ATTN_1)  +        ) & TX_ATTN_MASK; + +    UHD_LOGV(often) << boost::format( +        "WBX TX Attenuation: %f dB, Code: %d, IO Bits %x, Mask: %x" +    ) % attn % attn_code % (iobits & TX_ATTN_MASK) % TX_ATTN_MASK << std::endl; + +    //the actual gain setting +    gain = wbx_v4_tx_gain_ranges["PGA0"].stop() - double(attn_code); + +    return iobits; +} + + +/*********************************************************************** + * WBX Common Implementation + **********************************************************************/ +wbx_base::wbx_version4::wbx_version4(wbx_base *_self_wbx_base) { +    //register our handle on the primary wbx_base instance +    self_base = _self_wbx_base; + +    //////////////////////////////////////////////////////////////////// +    // Register RX properties +    //////////////////////////////////////////////////////////////////// +    this->get_rx_subtree()->create<std::string>("name").set("WBXv4 RX"); +    this->get_rx_subtree()->create<double>("freq/value") +         .coerce(boost::bind(&wbx_base::wbx_version4::set_lo_freq, this, dboard_iface::UNIT_RX, _1)) +         .set((wbx_v4_freq_range.start() + wbx_v4_freq_range.stop())/2.0); +    this->get_rx_subtree()->create<meta_range_t>("freq/range").set(wbx_v4_freq_range); + +    //////////////////////////////////////////////////////////////////// +    // Register TX properties +    //////////////////////////////////////////////////////////////////// +    this->get_tx_subtree()->create<std::string>("name").set("WBXv4 TX"); +    BOOST_FOREACH(const std::string &name, wbx_v4_tx_gain_ranges.keys()){ +        self_base->get_tx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&wbx_base::wbx_version4::set_tx_gain, this, _1, name)) +            .set(wbx_v4_tx_gain_ranges[name].start()); +        self_base->get_tx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(wbx_v4_tx_gain_ranges[name]); +    } +    this->get_tx_subtree()->create<double>("freq/value") +         .coerce(boost::bind(&wbx_base::wbx_version4::set_lo_freq, this, dboard_iface::UNIT_TX, _1)) +         .set((wbx_v4_freq_range.start() + wbx_v4_freq_range.stop())/2.0); +    this->get_tx_subtree()->create<meta_range_t>("freq/range").set(wbx_v4_freq_range); +    this->get_tx_subtree()->create<bool>("enabled") +        .subscribe(boost::bind(&wbx_base::wbx_version4::set_tx_enabled, this, _1)) +        .set(true); //start enabled + +    //set attenuator control bits +    int v4_iobits = TX_ATTN_MASK; +    int v4_tx_mod = ADF4351_PDBRF; + +    //set the gpio directions and atr controls +    self_base->get_iface()->set_pin_ctrl(dboard_iface::UNIT_TX, v4_tx_mod|v4_iobits); +    self_base->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, RXBB_PDB|ADF4351_PDBRF); +    self_base->get_iface()->set_gpio_ddr(dboard_iface::UNIT_TX, TX_PUP_5V|TX_PUP_3V|v4_tx_mod|v4_iobits); +    self_base->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, RX_PUP_5V|RX_PUP_3V|ADF4351_CE|RXBB_PDB|ADF4351_PDBRF|RX_ATTN_MASK); + +    //setup ATR for the mixer enables (always enabled to prevent phase slip between bursts) +    //set TX gain iobits to min gain (max attenuation) when RX_ONLY or IDLE to suppress LO leakage +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_IDLE,        v4_tx_mod, TX_ATTN_MASK | TX_MIXER_DIS | v4_tx_mod); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_RX_ONLY,     v4_tx_mod, TX_ATTN_MASK | TX_MIXER_DIS | v4_tx_mod); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     v4_tx_mod, TX_ATTN_MASK | TX_MIXER_DIS | v4_tx_mod); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, v4_tx_mod, TX_ATTN_MASK | TX_MIXER_DIS | v4_tx_mod); + +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_IDLE,        RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_TX_ONLY,     RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_RX_ONLY,     RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +    self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_FULL_DUPLEX, RX_MIXER_ENB, RX_MIXER_DIS | RX_MIXER_ENB); +} + +wbx_base::wbx_version4::~wbx_version4(void){ +    /* NOP */ +} + + +/*********************************************************************** + * Enables + **********************************************************************/ +void wbx_base::wbx_version4::set_tx_enabled(bool enb) { +    self_base->get_iface()->set_gpio_out(dboard_iface::UNIT_TX, +        (enb)? TX_POWER_UP | ADF4351_CE : TX_POWER_DOWN, TX_POWER_UP | TX_POWER_DOWN | 0); +} + + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +double wbx_base::wbx_version4::set_tx_gain(double gain, const std::string &name) { +    assert_has(wbx_v4_tx_gain_ranges.keys(), name, "wbx tx gain name"); +    if(name == "PGA0"){ +        boost::uint16_t io_bits = tx_pga0_gain_to_iobits(gain); + +        self_base->_tx_gains[name] = gain; + +        //write the new gain to tx gpio outputs +        //Update ATR with gain io_bits, only update for TX_ONLY and FULL_DUPLEX ATR states +        self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     io_bits, TX_ATTN_MASK); +        self_base->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, io_bits, TX_ATTN_MASK); + +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    return self_base->_tx_gains[name]; +} + + +/*********************************************************************** + * Tuning + **********************************************************************/ +double wbx_base::wbx_version4::set_lo_freq(dboard_iface::unit_t unit, double target_freq) { +    //clip to tuning range +    target_freq = wbx_v4_freq_range.clip(target_freq); + +    UHD_LOGV(often) << boost::format( +        "WBX tune: target frequency %f Mhz" +    ) % (target_freq/1e6) << std::endl; + +    //start with target_freq*2 because mixer has divide by 2 +    target_freq *= 2; + +    //map prescaler setting to mininmum integer divider (N) values (pg.18 prescaler) +    static const uhd::dict<int, int> prescaler_to_min_int_div = map_list_of +        (0,23) //adf4351_regs_t::PRESCALER_4_5 +        (1,75) //adf4351_regs_t::PRESCALER_8_9 +    ; + +    //map rf divider select output dividers to enums +    static const uhd::dict<int, adf4351_regs_t::rf_divider_select_t> rfdivsel_to_enum = map_list_of +        (1,  adf4351_regs_t::RF_DIVIDER_SELECT_DIV1) +        (2,  adf4351_regs_t::RF_DIVIDER_SELECT_DIV2) +        (4,  adf4351_regs_t::RF_DIVIDER_SELECT_DIV4) +        (8,  adf4351_regs_t::RF_DIVIDER_SELECT_DIV8) +        (16, adf4351_regs_t::RF_DIVIDER_SELECT_DIV16) +        (32, adf4351_regs_t::RF_DIVIDER_SELECT_DIV32) +        (64, adf4351_regs_t::RF_DIVIDER_SELECT_DIV64) +    ; + +    double actual_freq, pfd_freq; +    double ref_freq = self_base->get_iface()->get_clock_rate(unit); +    int R=0, BS=0, N=0, FRAC=0, MOD=0; +    int RFdiv = 1; +    adf4351_regs_t::reference_divide_by_2_t T     = adf4351_regs_t::REFERENCE_DIVIDE_BY_2_DISABLED; +    adf4351_regs_t::reference_doubler_t     D     = adf4351_regs_t::REFERENCE_DOUBLER_DISABLED;     + +    //Reference doubler for 50% duty cycle +    // if ref_freq < 12.5MHz enable regs.reference_divide_by_2 +    if(ref_freq <= 12.5e6) D = adf4351_regs_t::REFERENCE_DOUBLER_ENABLED; + +    //increase RF divider until acceptable VCO frequency +    const bool do_sync = (target_freq/2 > ref_freq); +    double vco_freq = target_freq; +    while (vco_freq < 2.2e9) { +        vco_freq *= 2; +        RFdiv *= 2; +    } +    if (do_sync) vco_freq = target_freq; + +    //use 8/9 prescaler for vco_freq > 3 GHz (pg.18 prescaler) +    adf4351_regs_t::prescaler_t prescaler = vco_freq > 3e9 ? adf4351_regs_t::PRESCALER_8_9 : adf4351_regs_t::PRESCALER_4_5; + +    /* +     * The goal here is to loop though possible R dividers, +     * band select clock dividers, N (int) dividers, and FRAC  +     * (frac) dividers. +     * +     * Calculate the N and F dividers for each set of values. +     * The loop exits when it meets all of the constraints. +     * The resulting loop values are loaded into the registers. +     * +     * from pg.21 +     * +     * f_pfd = f_ref*(1+D)/(R*(1+T)) +     * f_vco = (N + (FRAC/MOD))*f_pfd +     *    N = f_vco/f_pfd - FRAC/MOD = f_vco*((R*(T+1))/(f_ref*(1+D))) - FRAC/MOD +     * f_rf = f_vco/RFdiv) +     * f_actual = f_rf/2 +     */ +    for(R = 1; R <= 1023; R+=1){ +        //PFD input frequency = f_ref/R ... ignoring Reference doubler/divide-by-2 (D & T) +        pfd_freq = ref_freq*(1+D)/(R*(1+T)); + +        //keep the PFD frequency at or below 25MHz (Loop Filter Bandwidth) +        if (pfd_freq > 25e6) continue; + +        //ignore fractional part of tuning +        N = int(std::floor(vco_freq/pfd_freq)); + +        //keep N > minimum int divider requirement +        if (N < prescaler_to_min_int_div[prescaler]) continue; + +        for(BS=1; BS <= 255; BS+=1){ +            //keep the band select frequency at or below 100KHz +            //constraint on band select clock +            if (pfd_freq/BS > 100e3) continue; +            goto done_loop; +        } +    } done_loop: + +    //Fractional-N calculation +    MOD = 4095; //max fractional accuracy +    FRAC = int((vco_freq/pfd_freq - N)*MOD); + +    //Reference divide-by-2 for 50% duty cycle +    // if R even, move one divide by 2 to to regs.reference_divide_by_2 +    if(R % 2 == 0){ +        T = adf4351_regs_t::REFERENCE_DIVIDE_BY_2_ENABLED; +        R /= 2; +    } + +    //actual frequency calculation +    actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))/2/(vco_freq/target_freq)); + +    UHD_LOGV(often) +        << boost::format("WBX Intermediates: ref=%0.2f, outdiv=%f, fbdiv=%f") % (ref_freq*(1+int(D))/(R*(1+int(T)))) % double(RFdiv*2) % double(N + double(FRAC)/double(MOD)) << std::endl + +        << boost::format("WBX tune: R=%d, BS=%d, N=%d, FRAC=%d, MOD=%d, T=%d, D=%d, RFdiv=%d" +            ) % R % BS % N % FRAC % MOD % T % D % RFdiv << std::endl +        << boost::format("WBX Frequencies (MHz): REQ=%0.2f, ACT=%0.2f, VCO=%0.2f, PFD=%0.2f, BAND=%0.2f" +            ) % (target_freq/1e6) % (actual_freq/1e6) % (vco_freq/1e6) % (pfd_freq/1e6) % (pfd_freq/BS/1e6) << std::endl; + +    //load the register values +    adf4351_regs_t regs; + +    regs.frac_12_bit = FRAC; +    regs.int_16_bit = N; +    regs.mod_12_bit = MOD; +    if (do_sync) +    { +        regs.clock_divider_12_bit = std::max(1, int(std::ceil(400e-6*pfd_freq/MOD))); +        regs.feedback_select = adf4351_regs_t::FEEDBACK_SELECT_DIVIDED; +        regs.clock_div_mode = adf4351_regs_t::CLOCK_DIV_MODE_RESYNC_ENABLE; +    } +    regs.prescaler = prescaler; +    regs.r_counter_10_bit = R; +    regs.reference_divide_by_2 = T; +    regs.reference_doubler = D; +    regs.band_select_clock_div = BS; +    UHD_ASSERT_THROW(rfdivsel_to_enum.has_key(RFdiv)); +    regs.rf_divider_select = rfdivsel_to_enum[RFdiv]; + +    if (unit == dboard_iface::UNIT_RX) { +        freq_range_t rx_lo_5dbm = list_of +            (range_t(0.05e9, 1.4e9)) +        ; + +        freq_range_t rx_lo_2dbm = list_of +            (range_t(1.4e9, 2.2e9)) +        ; + +        if (actual_freq == rx_lo_5dbm.clip(actual_freq)) regs.output_power = adf4351_regs_t::OUTPUT_POWER_5DBM; + +        if (actual_freq == rx_lo_2dbm.clip(actual_freq)) regs.output_power = adf4351_regs_t::OUTPUT_POWER_2DBM; + +    } else if (unit == dboard_iface::UNIT_TX) { +        freq_range_t tx_lo_5dbm = list_of +            (range_t(0.05e9, 1.7e9)) +            (range_t(1.9e9, 2.2e9)) +        ; + +        freq_range_t tx_lo_m1dbm = list_of +            (range_t(1.7e9, 1.9e9)) +        ; + +        if (actual_freq == tx_lo_5dbm.clip(actual_freq)) regs.output_power = adf4351_regs_t::OUTPUT_POWER_5DBM; + +        if (actual_freq == tx_lo_m1dbm.clip(actual_freq)) regs.output_power = adf4351_regs_t::OUTPUT_POWER_M1DBM; + +    } + +    //write the registers +    //correct power-up sequence to write registers (5, 4, 3, 2, 1, 0) +    int addr; + +    for(addr=5; addr>=0; addr--){ +        UHD_LOGV(often) << boost::format( +            "WBX SPI Reg (0x%02x): 0x%08x" +        ) % addr % regs.get_reg(addr) << std::endl; +        self_base->get_iface()->write_spi( +            unit, spi_config_t::EDGE_RISE, +            regs.get_reg(addr), 32 +        ); +    } + +    //return the actual frequency +    UHD_LOGV(often) << boost::format( +        "WBX tune: actual frequency %f Mhz" +    ) % (actual_freq/1e6) << std::endl; +    return actual_freq; +} diff --git a/host/lib/usrp/dboard/db_xcvr2450.cpp b/host/lib/usrp/dboard/db_xcvr2450.cpp new file mode 100644 index 000000000..da894fc9b --- /dev/null +++ b/host/lib/usrp/dboard/db_xcvr2450.cpp @@ -0,0 +1,673 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +// TX IO Pins +#define HB_PA_OFF_TXIO      (1 << 15)    // 5GHz PA, 1 = off, 0 = on +#define LB_PA_OFF_TXIO      (1 << 14)    // 2.4GHz PA, 1 = off, 0 = on +#define ANTSEL_TX1_RX2_TXIO (1 << 13)    // 1 = Ant 1 to TX, Ant 2 to RX +#define ANTSEL_TX2_RX1_TXIO (1 << 12)    // 1 = Ant 2 to TX, Ant 1 to RX +#define TX_EN_TXIO          (1 << 11)    // 1 = TX on, 0 = TX off +#define AD9515DIV_TXIO      (1 << 4)     // 1 = Div  by 3, 0 = Div by 2 + +#define TXIO_MASK (HB_PA_OFF_TXIO | LB_PA_OFF_TXIO | ANTSEL_TX1_RX2_TXIO | ANTSEL_TX2_RX1_TXIO | TX_EN_TXIO | AD9515DIV_TXIO) + +// TX IO Functions +#define HB_PA_TXIO               LB_PA_OFF_TXIO +#define LB_PA_TXIO               HB_PA_OFF_TXIO +#define TX_ENB_TXIO              TX_EN_TXIO +#define TX_DIS_TXIO              0 +#define AD9515DIV_3_TXIO         AD9515DIV_TXIO +#define AD9515DIV_2_TXIO         0 + +// RX IO Pins +#define LOCKDET_RXIO (1 << 15)           // This is an INPUT!!! +#define POWER_RXIO   (1 << 14)           // 1 = power on, 0 = shutdown +#define RX_EN_RXIO   (1 << 13)           // 1 = RX on, 0 = RX off +#define RX_HP_RXIO   (1 << 12)           // 0 = Fc set by rx_hpf, 1 = 600 KHz + +#define RXIO_MASK (POWER_RXIO | RX_EN_RXIO | RX_HP_RXIO) + +// RX IO Functions +#define POWER_UP_RXIO            POWER_RXIO +#define POWER_DOWN_RXIO          0 +#define RX_ENB_RXIO              RX_EN_RXIO +#define RX_DIS_RXIO              0 + +#include "max2829_regs.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/safe_call.hpp> +#include <uhd/utils/assert_has.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/thread.hpp> +#include <boost/math/special_functions/round.hpp> +#include <utility> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +/*********************************************************************** + * The XCVR 2450 constants + **********************************************************************/ +static const freq_range_t xcvr_freq_range = list_of +    (range_t(2.4e9, 2.5e9)) +    (range_t(4.9e9, 6.0e9)) +; + +//Multiplied by 2.0 for conversion to complex bandpass from lowpass +static const freq_range_t xcvr_tx_bandwidth_range = list_of +    (range_t(2.0*12e6)) +    (range_t(2.0*18e6)) +    (range_t(2.0*24e6)) +; + +//Multiplied by 2.0 for conversion to complex bandpass from lowpass +static const freq_range_t xcvr_rx_bandwidth_range = list_of +    (range_t(2.0*0.9*7.5e6, 2.0*1.1*7.5e6)) +    (range_t(2.0*0.9*9.5e6, 2.0*1.1*9.5e6)) +    (range_t(2.0*0.9*14e6,  2.0*1.1*14e6)) +    (range_t(2.0*0.9*18e6,  2.0*1.1*18e6)) +; + +static const std::vector<std::string> xcvr_antennas = list_of("J1")("J2"); + +static const uhd::dict<std::string, gain_range_t> xcvr_tx_gain_ranges = map_list_of +    ("VGA", gain_range_t(0, 30, 0.5)) +    ("BB", gain_range_t(0, 5, 1.5)) +; +static const uhd::dict<std::string, gain_range_t> xcvr_rx_gain_ranges = map_list_of +    ("LNA", gain_range_t(list_of +        (range_t(0)) +        (range_t(15)) +        (range_t(30.5)) +    )) +    ("VGA", gain_range_t(0, 62, 2.0)) +; + +/*********************************************************************** + * The XCVR 2450 dboard class + **********************************************************************/ +class xcvr2450 : public xcvr_dboard_base{ +public: +    xcvr2450(ctor_args_t args); +    ~xcvr2450(void); + +private: +    double _lo_freq; +    double _rx_bandwidth, _tx_bandwidth; +    uhd::dict<std::string, double> _tx_gains, _rx_gains; +    std::string _tx_ant, _rx_ant; +    int _ad9515div; +    max2829_regs_t _max2829_regs; + +    double set_lo_freq(double target_freq); +    double set_lo_freq_core(double target_freq); +    void set_tx_ant(const std::string &ant); +    void set_rx_ant(const std::string &ant); +    double set_tx_gain(double gain, const std::string &name); +    double set_rx_gain(double gain, const std::string &name); +    double set_rx_bandwidth(double bandwidth); +    double set_tx_bandwidth(double bandwidth); + +    void update_atr(void); +    void spi_reset(void); +    void send_reg(boost::uint8_t addr){ +        boost::uint32_t value = _max2829_regs.get_reg(addr); +        UHD_LOGV(often) << boost::format( +            "XCVR2450: send reg 0x%02x, value 0x%05x" +        ) % int(addr) % value << std::endl; +        this->get_iface()->write_spi( +            dboard_iface::UNIT_RX, +            spi_config_t::EDGE_RISE, +            value, 24 +        ); +    } + +    static bool is_highband(double freq){return freq > 3e9;} + +    /*! +     * Get the lock detect status of the LO. +     * \return sensor for locked +     */ +    sensor_value_t get_locked(void){ +        const bool locked = (this->get_iface()->read_gpio(dboard_iface::UNIT_RX) & LOCKDET_RXIO) != 0; +        return sensor_value_t("LO", locked, "locked", "unlocked"); +    } + +    /*! +     * Read the RSSI from the aux adc +     * \return the rssi sensor in dBm +     */ +    sensor_value_t get_rssi(void){ +        //*FIXME* RSSI depends on LNA Gain Setting (datasheet pg 16 top middle chart) +        double max_power = 0.0; +        switch(_max2829_regs.rx_lna_gain){ +        case 0: +        case 1: max_power = 0;    break; +        case 2: max_power = -15;   break; +        case 3: max_power = -30.5; break; +        } + +        //constants for the rssi calculation +        static const double min_v = 2.5, max_v = 0.5; +        static const double rssi_dyn_range = 60.0; +        //calculate the rssi from the voltage +        double voltage = this->get_iface()->read_aux_adc(dboard_iface::UNIT_RX, dboard_iface::AUX_ADC_B); +        double rssi = max_power - rssi_dyn_range*(voltage - min_v)/(max_v - min_v); +        return sensor_value_t("RSSI", rssi, "dBm"); +    } +}; + +/*********************************************************************** + * Register the XCVR 2450 dboard + **********************************************************************/ +static dboard_base::sptr make_xcvr2450(dboard_base::ctor_args_t args){ +    return dboard_base::sptr(new xcvr2450(args)); +} + +UHD_STATIC_BLOCK(reg_xcvr2450_dboard){ +    //register the factory function for the rx and tx dbids +    dboard_manager::register_dboard(0x0061, 0x0060, &make_xcvr2450, "XCVR2450"); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +xcvr2450::xcvr2450(ctor_args_t args) : xcvr_dboard_base(args){ +    spi_reset(); //prepare the spi + +    _rx_bandwidth = 9.5e6; +    _tx_bandwidth = 12.0e6; + +    //setup the misc max2829 registers +    _max2829_regs.mimo_select         = max2829_regs_t::MIMO_SELECT_MIMO; +    _max2829_regs.band_sel_mimo       = max2829_regs_t::BAND_SEL_MIMO_MIMO; +    _max2829_regs.pll_cp_select       = max2829_regs_t::PLL_CP_SELECT_4MA; +    _max2829_regs.rssi_high_bw        = max2829_regs_t::RSSI_HIGH_BW_6MHZ; +    _max2829_regs.tx_lpf_coarse_adj   = max2829_regs_t::TX_LPF_COARSE_ADJ_12MHZ; +    _max2829_regs.rx_lpf_coarse_adj   = max2829_regs_t::RX_LPF_COARSE_ADJ_9_5MHZ; +    _max2829_regs.rx_lpf_fine_adj     = max2829_regs_t::RX_LPF_FINE_ADJ_100; +    _max2829_regs.rx_vga_gain_spi     = max2829_regs_t::RX_VGA_GAIN_SPI_SPI; +    _max2829_regs.rssi_output_range   = max2829_regs_t::RSSI_OUTPUT_RANGE_HIGH; +    _max2829_regs.rssi_op_mode        = max2829_regs_t::RSSI_OP_MODE_ENABLED; +    _max2829_regs.rssi_pin_fcn        = max2829_regs_t::RSSI_PIN_FCN_RSSI; +    _max2829_regs.rx_highpass         = max2829_regs_t::RX_HIGHPASS_100HZ; +    _max2829_regs.tx_vga_gain_spi     = max2829_regs_t::TX_VGA_GAIN_SPI_SPI; +    _max2829_regs.pa_driver_linearity = max2829_regs_t::PA_DRIVER_LINEARITY_78; +    _max2829_regs.tx_vga_linearity    = max2829_regs_t::TX_VGA_LINEARITY_78; +    _max2829_regs.tx_upconv_linearity = max2829_regs_t::TX_UPCONV_LINEARITY_78; + +    //send initial register settings +    for(boost::uint8_t reg = 0x2; reg <= 0xC; reg++){ +        this->send_reg(reg); +    } + +    //////////////////////////////////////////////////////////////////// +    // Register RX properties +    //////////////////////////////////////////////////////////////////// +    this->get_rx_subtree()->create<std::string>("name") +        .set("XCVR2450 RX"); +    this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&xcvr2450::get_locked, this)); +    this->get_rx_subtree()->create<sensor_value_t>("sensors/rssi") +        .publish(boost::bind(&xcvr2450::get_rssi, this)); +    BOOST_FOREACH(const std::string &name, xcvr_rx_gain_ranges.keys()){ +        this->get_rx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&xcvr2450::set_rx_gain, this, _1, name)) +            .set(xcvr_rx_gain_ranges[name].start()); +        this->get_rx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(xcvr_rx_gain_ranges[name]); +    } +    this->get_rx_subtree()->create<double>("freq/value") +        .coerce(boost::bind(&xcvr2450::set_lo_freq, this, _1)) +        .set(double(2.45e9)); +    this->get_rx_subtree()->create<meta_range_t>("freq/range") +        .set(xcvr_freq_range); +    this->get_rx_subtree()->create<std::string>("antenna/value") +        .subscribe(boost::bind(&xcvr2450::set_rx_ant, this, _1)) +        .set(xcvr_antennas.at(0)); +    this->get_rx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(xcvr_antennas); +    this->get_rx_subtree()->create<std::string>("connection") +        .set("IQ"); +    this->get_rx_subtree()->create<bool>("enabled") +        .set(true); //always enabled +    this->get_rx_subtree()->create<bool>("use_lo_offset") +        .set(false); +    this->get_rx_subtree()->create<double>("bandwidth/value") +        .coerce(boost::bind(&xcvr2450::set_rx_bandwidth, this, _1)) //complex bandpass bandwidth  +        .set(2.0*_rx_bandwidth); //_rx_bandwidth in lowpass, convert to complex bandpass +    this->get_rx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(xcvr_rx_bandwidth_range); + +    //////////////////////////////////////////////////////////////////// +    // Register TX properties +    //////////////////////////////////////////////////////////////////// +    this->get_tx_subtree()->create<std::string>("name") +        .set("XCVR2450 TX"); +    this->get_tx_subtree()->create<sensor_value_t>("sensors/lo_locked") +        .publish(boost::bind(&xcvr2450::get_locked, this)); +    BOOST_FOREACH(const std::string &name, xcvr_tx_gain_ranges.keys()){ +        this->get_tx_subtree()->create<double>("gains/"+name+"/value") +            .coerce(boost::bind(&xcvr2450::set_tx_gain, this, _1, name)) +            .set(xcvr_tx_gain_ranges[name].start()); +        this->get_tx_subtree()->create<meta_range_t>("gains/"+name+"/range") +            .set(xcvr_tx_gain_ranges[name]); +    } +    this->get_tx_subtree()->create<double>("freq/value") +        .coerce(boost::bind(&xcvr2450::set_lo_freq, this, _1)) +        .set(double(2.45e9)); +    this->get_tx_subtree()->create<meta_range_t>("freq/range") +        .set(xcvr_freq_range); +    this->get_tx_subtree()->create<std::string>("antenna/value") +        .subscribe(boost::bind(&xcvr2450::set_tx_ant, this, _1)) +        .set(xcvr_antennas.at(1)); +    this->get_tx_subtree()->create<std::vector<std::string> >("antenna/options") +        .set(xcvr_antennas); +    this->get_tx_subtree()->create<std::string>("connection") +        .set("QI"); +    this->get_tx_subtree()->create<bool>("enabled") +        .set(true); //always enabled +    this->get_tx_subtree()->create<bool>("use_lo_offset") +        .set(false); +    this->get_tx_subtree()->create<double>("bandwidth/value") +        .coerce(boost::bind(&xcvr2450::set_tx_bandwidth, this, _1)) //complex bandpass bandwidth +        .set(2.0*_tx_bandwidth); //_tx_bandwidth in lowpass, convert to complex bandpass +    this->get_tx_subtree()->create<meta_range_t>("bandwidth/range") +        .set(xcvr_tx_bandwidth_range); + +    //enable only the clocks we need +    this->get_iface()->set_clock_enabled(dboard_iface::UNIT_TX, true); + +    //set the gpio directions and atr controls (identically) +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_TX, TXIO_MASK); +    this->get_iface()->set_pin_ctrl(dboard_iface::UNIT_RX, RXIO_MASK); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_TX, TXIO_MASK); +    this->get_iface()->set_gpio_ddr(dboard_iface::UNIT_RX, RXIO_MASK); +} + +xcvr2450::~xcvr2450(void){ +    UHD_SAFE_CALL(spi_reset();) +} + +void xcvr2450::spi_reset(void){ +    //spi reset mode: global enable = off, tx and rx enable = on +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_IDLE, TX_ENB_TXIO); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_IDLE, RX_ENB_RXIO | POWER_DOWN_RXIO); +    boost::this_thread::sleep(boost::posix_time::milliseconds(10)); + +    //take it back out of spi reset mode and wait a bit +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_IDLE, RX_DIS_RXIO | POWER_UP_RXIO); +    boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +} + +/*********************************************************************** + * Update ATR regs which change with Antenna or Freq + **********************************************************************/ +void xcvr2450::update_atr(void){ +    //calculate tx atr pins +    int band_sel   = (xcvr2450::is_highband(_lo_freq))? HB_PA_TXIO : LB_PA_TXIO; +    int tx_ant_sel = (_tx_ant == "J1")? ANTSEL_TX1_RX2_TXIO : ANTSEL_TX2_RX1_TXIO; +    int rx_ant_sel = (_rx_ant == "J2")? ANTSEL_TX1_RX2_TXIO : ANTSEL_TX2_RX1_TXIO; +    int xx_ant_sel = tx_ant_sel; //Prefer the tx antenna selection for full duplex, +    //due to the issue that USRP1 will take the value of full duplex for its TXATR. +    int ad9515div  = (_ad9515div == 3)? AD9515DIV_3_TXIO : AD9515DIV_2_TXIO; + +    //set the tx registers +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_IDLE,        band_sel | ad9515div | TX_DIS_TXIO); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_RX_ONLY,     band_sel | ad9515div | TX_DIS_TXIO | rx_ant_sel); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_TX_ONLY,     band_sel | ad9515div | TX_ENB_TXIO | tx_ant_sel); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_TX, dboard_iface::ATR_REG_FULL_DUPLEX, band_sel | ad9515div | TX_ENB_TXIO | xx_ant_sel); + +    //set the rx registers +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_IDLE,        POWER_UP_RXIO | RX_DIS_RXIO); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_RX_ONLY,     POWER_UP_RXIO | RX_ENB_RXIO); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_TX_ONLY,     POWER_UP_RXIO | RX_DIS_RXIO); +    this->get_iface()->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_FULL_DUPLEX, POWER_UP_RXIO | RX_DIS_RXIO); +} + +/*********************************************************************** + * Tuning + **********************************************************************/ +double xcvr2450::set_lo_freq(double target_freq){ +    //tune the LO and sleep a bit for lock +    //if not locked, try some carrier offsets +    double actual = 0.0; +    for (double offset = 0.0; offset <= 3e6; offset+=1e6){ +        actual = this->set_lo_freq_core(target_freq + offset); +        boost::this_thread::sleep(boost::posix_time::milliseconds(50)); +        if (this->get_locked().to_bool()) break; +    } +    return actual; +} + +double xcvr2450::set_lo_freq_core(double target_freq){ + +    //clip the input to the range +    target_freq = xcvr_freq_range.clip(target_freq); + +    //variables used in the calculation below +    double scaler = xcvr2450::is_highband(target_freq)? (4.0/5.0) : (4.0/3.0); +    double ref_freq = this->get_iface()->get_clock_rate(dboard_iface::UNIT_TX); +    int R, intdiv, fracdiv; + +    //loop through values until we get a match +    for(_ad9515div = 2; _ad9515div <= 3; _ad9515div++){ +        for(R = 1; R <= 7; R++){ +            double N = (target_freq*scaler*R*_ad9515div)/ref_freq; +            intdiv = int(std::floor(N)); +            fracdiv = boost::math::iround((N - intdiv)*double(1 << 16)); +            //actual minimum is 128, but most chips seems to require higher to lock +            if (intdiv < 131 or intdiv > 255) continue; +            //constraints met: exit loop +            goto done_loop; +        } +    } done_loop: + +    //calculate the actual freq from the values above +    double N = double(intdiv) + double(fracdiv)/double(1 << 16); +    _lo_freq = (N*ref_freq)/(scaler*R*_ad9515div); + +    UHD_LOGV(often) +        << boost::format("XCVR2450 tune:\n") +        << boost::format("    R=%d, N=%f, ad9515=%d, scaler=%f\n") % R % N % _ad9515div % scaler +        << boost::format("    Ref    Freq=%fMHz\n") % (ref_freq/1e6) +        << boost::format("    Target Freq=%fMHz\n") % (target_freq/1e6) +        << boost::format("    Actual Freq=%fMHz\n") % (_lo_freq/1e6) +        << std::endl; + +    //high-high band or low-high band? +    if(_lo_freq > (5.35e9 + 5.47e9)/2.0){ +        UHD_LOGV(often) << "XCVR2450 tune: Using  high-high band" << std::endl; +        _max2829_regs.band_select_802_11a = max2829_regs_t::BAND_SELECT_802_11A_5_47GHZ_TO_5_875GHZ; +    }else{ +        UHD_LOGV(often) << "XCVR2450 tune: Using  low-high band" << std::endl; +        _max2829_regs.band_select_802_11a = max2829_regs_t::BAND_SELECT_802_11A_4_9GHZ_TO_5_35GHZ; +    } + +    //new band select settings and ad9515 divider +    this->update_atr(); + +    //load new counters into registers +    _max2829_regs.int_div_ratio_word = intdiv; +    _max2829_regs.frac_div_ratio_lsb = fracdiv & 0x3; +    _max2829_regs.frac_div_ratio_msb = fracdiv >> 2; +    this->send_reg(0x3); //integer +    this->send_reg(0x4); //fractional + +    //load the reference divider and band select into registers +    //toggle the bandswitch from off to automatic (which really means start) +    _max2829_regs.ref_divider = R; +    _max2829_regs.band_select = (xcvr2450::is_highband(_lo_freq))? +                                max2829_regs_t::BAND_SELECT_5GHZ   : +                                max2829_regs_t::BAND_SELECT_2_4GHZ ; +    _max2829_regs.vco_bandswitch = max2829_regs_t::VCO_BANDSWITCH_DISABLE; +    this->send_reg(0x5); +    _max2829_regs.vco_bandswitch = max2829_regs_t::VCO_BANDSWITCH_AUTOMATIC;; +    this->send_reg(0x5); + +    return _lo_freq; +} + +/*********************************************************************** + * Antenna Handling + **********************************************************************/ +void xcvr2450::set_tx_ant(const std::string &ant){ +    assert_has(xcvr_antennas, ant, "xcvr antenna name"); +   _tx_ant = ant; +    this->update_atr(); //sets the atr to the new antenna setting +} + +void xcvr2450::set_rx_ant(const std::string &ant){ +    assert_has(xcvr_antennas, ant, "xcvr antenna name"); +    _rx_ant = ant; +    this->update_atr(); //sets the atr to the new antenna setting +} + +/*********************************************************************** + * Gain Handling + **********************************************************************/ +/*! + * Convert a requested gain for the tx vga into the integer register value. + * The gain passed into the function will be set to the actual value. + * \param gain the requested gain in dB + * \return 6 bit the register value + */ +static int gain_to_tx_vga_reg(double &gain){ +    //calculate the register value +    int reg = uhd::clip(boost::math::iround(gain*60/30.0) + 3, 0, 63); + +    //calculate the actual gain value +    if (reg < 4)       gain = 0; +    else if (reg < 48) gain = double(reg/2 - 1); +    else               gain = double(reg/2.0 - 1.5); + +    //return register value +    return reg; +} + +/*! + * Convert a requested gain for the tx bb into the integer register value. + * The gain passed into the function will be set to the actual value. + * \param gain the requested gain in dB + * \return gain enum value + */ +static max2829_regs_t::tx_baseband_gain_t gain_to_tx_bb_reg(double &gain){ +    int reg = uhd::clip(boost::math::iround(gain*3/5.0), 0, 3); +    switch(reg){ +    case 0: +        gain = 0; +        return max2829_regs_t::TX_BASEBAND_GAIN_0DB; +    case 1: +        gain = 2; +        return max2829_regs_t::TX_BASEBAND_GAIN_2DB; +    case 2: +        gain = 3.5; +        return max2829_regs_t::TX_BASEBAND_GAIN_3_5DB; +    case 3: +        gain = 5; +        return max2829_regs_t::TX_BASEBAND_GAIN_5DB; +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +/*! + * Convert a requested gain for the rx vga into the integer register value. + * The gain passed into the function will be set to the actual value. + * \param gain the requested gain in dB + * \return 5 bit the register value + */ +static int gain_to_rx_vga_reg(double &gain){ +    int reg = uhd::clip(boost::math::iround(gain/2.0), 0, 31); +    gain = double(reg*2); +    return reg; +} + +/*! + * Convert a requested gain for the rx lna into the integer register value. + * The gain passed into the function will be set to the actual value. + * \param gain the requested gain in dB + * \return 2 bit the register value + */ +static int gain_to_rx_lna_reg(double &gain){ +    int reg = uhd::clip(boost::math::iround(gain*2/30.5) + 1, 0, 3); +    switch(reg){ +    case 0: +    case 1: gain = 0;    break; +    case 2: gain = 15;   break; +    case 3: gain = 30.5; break; +    } +    return reg; +} + +double xcvr2450::set_tx_gain(double gain, const std::string &name){ +    assert_has(xcvr_tx_gain_ranges.keys(), name, "xcvr tx gain name"); +    if (name == "VGA"){ +        _max2829_regs.tx_vga_gain = gain_to_tx_vga_reg(gain); +        send_reg(0xC); +    } +    else if(name == "BB"){ +        _max2829_regs.tx_baseband_gain = gain_to_tx_bb_reg(gain); +        send_reg(0x9); +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    _tx_gains[name] = gain; + +    return gain; +} + +double xcvr2450::set_rx_gain(double gain, const std::string &name){ +    assert_has(xcvr_rx_gain_ranges.keys(), name, "xcvr rx gain name"); +    if (name == "VGA"){ +        _max2829_regs.rx_vga_gain = gain_to_rx_vga_reg(gain); +        send_reg(0xB); +    } +    else if(name == "LNA"){ +        _max2829_regs.rx_lna_gain = gain_to_rx_lna_reg(gain); +        send_reg(0xB); +    } +    else UHD_THROW_INVALID_CODE_PATH(); +    _rx_gains[name] = gain; + +    return gain; +} + + +/*********************************************************************** + * Bandwidth Handling + **********************************************************************/ +static max2829_regs_t::tx_lpf_coarse_adj_t bandwidth_to_tx_lpf_coarse_reg(double &bandwidth){ +    int reg = uhd::clip(boost::math::iround((bandwidth-6.0e6)/6.0e6), 1, 3); + +    switch(reg){ +    case 1: // bandwidth < 15MHz +        bandwidth = 12e6; +        return max2829_regs_t::TX_LPF_COARSE_ADJ_12MHZ; +    case 2: // 15MHz < bandwidth < 21MHz +        bandwidth = 18e6; +        return max2829_regs_t::TX_LPF_COARSE_ADJ_18MHZ; +    case 3: // bandwidth > 21MHz +        bandwidth = 24e6; +        return max2829_regs_t::TX_LPF_COARSE_ADJ_24MHZ; +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +static max2829_regs_t::rx_lpf_fine_adj_t bandwidth_to_rx_lpf_fine_reg(double &bandwidth, double requested_bandwidth){ +    int reg = uhd::clip(boost::math::iround((requested_bandwidth/bandwidth)/0.05), 18, 22); + +    switch(reg){ +    case 18: // requested_bandwidth < 92.5% +        bandwidth = 0.9 * bandwidth; +        return max2829_regs_t::RX_LPF_FINE_ADJ_90; +    case 19: // 92.5% < requested_bandwidth < 97.5% +        bandwidth = 0.95 * bandwidth; +        return max2829_regs_t::RX_LPF_FINE_ADJ_95; +    case 20: // 97.5% < requested_bandwidth < 102.5% +        bandwidth = 1.0 * bandwidth; +        return max2829_regs_t::RX_LPF_FINE_ADJ_100; +    case 21: // 102.5% < requested_bandwidth < 107.5% +        bandwidth = 1.05 * bandwidth; +        return max2829_regs_t::RX_LPF_FINE_ADJ_105; +    case 22: // 107.5% < requested_bandwidth +        bandwidth = 1.1 * bandwidth; +        return max2829_regs_t::RX_LPF_FINE_ADJ_110; +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +static max2829_regs_t::rx_lpf_coarse_adj_t bandwidth_to_rx_lpf_coarse_reg(double &bandwidth){ +    int reg = uhd::clip(boost::math::iround((bandwidth-7.0e6)/1.0e6), 0, 11); + +    switch(reg){ +    case 0: // bandwidth < 7.5MHz +    case 1: // 7.5MHz < bandwidth < 8.5MHz +        bandwidth = 7.5e6; +        return max2829_regs_t::RX_LPF_COARSE_ADJ_7_5MHZ; +    case 2: // 8.5MHz < bandwidth < 9.5MHz +    case 3: // 9.5MHz < bandwidth < 10.5MHz +    case 4: // 10.5MHz < bandwidth < 11.5MHz +        bandwidth = 9.5e6; +        return max2829_regs_t::RX_LPF_COARSE_ADJ_9_5MHZ; +    case 5: // 11.5MHz < bandwidth < 12.5MHz +    case 6: // 12.5MHz < bandwidth < 13.5MHz +    case 7: // 13.5MHz < bandwidth < 14.5MHz +    case 8: // 14.5MHz < bandwidth < 15.5MHz +        bandwidth = 14e6; +        return max2829_regs_t::RX_LPF_COARSE_ADJ_14MHZ; +    case 9: // 15.5MHz < bandwidth < 16.5MHz +    case 10: // 16.5MHz < bandwidth < 17.5MHz +    case 11: // 17.5MHz < bandwidth +        bandwidth = 18e6; +        return max2829_regs_t::RX_LPF_COARSE_ADJ_18MHZ; +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +double xcvr2450::set_rx_bandwidth(double bandwidth){ +    double requested_bandwidth = bandwidth; + +    //convert complex bandpass to lowpass bandwidth +    bandwidth = bandwidth/2.0; + +    //compute coarse low pass cutoff frequency setting +    _max2829_regs.rx_lpf_coarse_adj = bandwidth_to_rx_lpf_coarse_reg(bandwidth); + +    //compute fine low pass cutoff frequency setting +    _max2829_regs.rx_lpf_fine_adj = bandwidth_to_rx_lpf_fine_reg(bandwidth, requested_bandwidth); + +    //shadow bandwidth setting +    _rx_bandwidth = bandwidth; + +    //update register +    send_reg(0x7); + +    UHD_LOGV(often) << boost::format( +        "XCVR2450 RX Bandwidth (lp_fc): %f Hz, coarse reg: %d, fine reg: %d" +    ) % _rx_bandwidth % (int(_max2829_regs.rx_lpf_coarse_adj)) % (int(_max2829_regs.rx_lpf_fine_adj)) << std::endl; + +    return 2.0*_rx_bandwidth; +} + +double xcvr2450::set_tx_bandwidth(double bandwidth){ +    //convert complex bandpass to lowpass bandwidth +    bandwidth = bandwidth/2.0; + +    //compute coarse low pass cutoff frequency setting +    _max2829_regs.tx_lpf_coarse_adj = bandwidth_to_tx_lpf_coarse_reg(bandwidth); + +    //shadow bandwidth setting +    _tx_bandwidth = bandwidth; + +    //update register +    send_reg(0x7); + +    UHD_LOGV(often) << boost::format( +        "XCVR2450 TX Bandwidth (lp_fc): %f Hz, coarse reg: %d" +    ) % _tx_bandwidth % (int(_max2829_regs.tx_lpf_coarse_adj)) << std::endl; + +    //convert lowpass back to complex bandpass bandwidth +    return 2.0*_tx_bandwidth; +} diff --git a/host/lib/usrp/dboard_base.cpp b/host/lib/usrp/dboard_base.cpp new file mode 100644 index 000000000..fe14c02b9 --- /dev/null +++ b/host/lib/usrp/dboard_base.cpp @@ -0,0 +1,100 @@ +// +// 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 "dboard_ctor_args.hpp" +#include <uhd/usrp/dboard_base.hpp> +#include <boost/format.hpp> +#include <stdexcept> + +using namespace uhd; +using namespace uhd::usrp; + +/*********************************************************************** + * dboard_base dboard dboard_base class + **********************************************************************/ +struct dboard_base::impl{ +    dboard_ctor_args_t args; +}; + +dboard_base::dboard_base(ctor_args_t args){ +    _impl = UHD_PIMPL_MAKE(impl, ()); +    _impl->args = *static_cast<dboard_ctor_args_t *>(args); +} + +std::string dboard_base::get_subdev_name(void){ +    return _impl->args.sd_name; +} + +dboard_iface::sptr dboard_base::get_iface(void){ +    return _impl->args.db_iface; +} + +dboard_id_t dboard_base::get_rx_id(void){ +    return _impl->args.rx_id; +} + +dboard_id_t dboard_base::get_tx_id(void){ +    return _impl->args.tx_id; +} + +property_tree::sptr dboard_base::get_rx_subtree(void){ +    return _impl->args.rx_subtree; +} + +property_tree::sptr dboard_base::get_tx_subtree(void){ +    return _impl->args.tx_subtree; +} + +/*********************************************************************** + * xcvr dboard dboard_base class + **********************************************************************/ +xcvr_dboard_base::xcvr_dboard_base(ctor_args_t args) : dboard_base(args){ +    if (get_rx_id() == dboard_id_t::none()){ +        throw uhd::runtime_error(str(boost::format( +            "cannot create xcvr board when the rx id is \"%s\"" +        ) % dboard_id_t::none().to_pp_string())); +    } +    if (get_tx_id() == dboard_id_t::none()){ +        throw uhd::runtime_error(str(boost::format( +            "cannot create xcvr board when the tx id is \"%s\"" +        ) % dboard_id_t::none().to_pp_string())); +    } +} + +/*********************************************************************** + * rx dboard dboard_base class + **********************************************************************/ +rx_dboard_base::rx_dboard_base(ctor_args_t args) : dboard_base(args){ +    if (get_tx_id() != dboard_id_t::none()){ +        throw uhd::runtime_error(str(boost::format( +            "cannot create rx board when the tx id is \"%s\"" +            " -> expected a tx id of \"%s\"" +        ) % get_tx_id().to_pp_string() % dboard_id_t::none().to_pp_string())); +    } +} + +/*********************************************************************** + * tx dboard dboard_base class + **********************************************************************/ +tx_dboard_base::tx_dboard_base(ctor_args_t args) : dboard_base(args){ +    if (get_rx_id() != dboard_id_t::none()){ +        throw uhd::runtime_error(str(boost::format( +            "cannot create tx board when the rx id is \"%s\"" +            " -> expected a rx id of \"%s\"" +        ) % get_rx_id().to_pp_string() % dboard_id_t::none().to_pp_string())); +    } +} diff --git a/host/lib/usrp/dboard_ctor_args.hpp b/host/lib/usrp/dboard_ctor_args.hpp new file mode 100644 index 000000000..99c071ff8 --- /dev/null +++ b/host/lib/usrp/dboard_ctor_args.hpp @@ -0,0 +1,38 @@ +// +// Copyright 2010 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_DBOARD_CTOR_ARGS_HPP +#define INCLUDED_LIBUHD_USRP_DBOARD_CTOR_ARGS_HPP + +#include <uhd/property_tree.hpp> +#include <uhd/usrp/dboard_id.hpp> +#include <uhd/usrp/dboard_base.hpp> +#include <uhd/usrp/dboard_iface.hpp> +#include <string> + +namespace uhd{ namespace usrp{ + +    struct dboard_ctor_args_t{ +        std::string               sd_name; +        dboard_iface::sptr        db_iface; +        dboard_id_t               rx_id, tx_id; +        property_tree::sptr       rx_subtree, tx_subtree; +    }; + +}} //namespace + +#endif /* INCLUDED_LIBUHD_USRP_DBOARD_CTOR_ARGS_HPP */ diff --git a/host/lib/usrp/dboard_eeprom.cpp b/host/lib/usrp/dboard_eeprom.cpp new file mode 100644 index 000000000..f2bee47a9 --- /dev/null +++ b/host/lib/usrp/dboard_eeprom.cpp @@ -0,0 +1,169 @@ +// +// 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/dboard_eeprom.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/log.hpp> +#include <boost/foreach.hpp> +#include <boost/format.hpp> +#include <boost/lexical_cast.hpp> +#include <algorithm> +#include <sstream> + +using namespace uhd; +using namespace uhd::usrp; + +/*********************************************************************** + * Utility functions + **********************************************************************/ + +//! create a string from a byte vector, return empty if invalid ascii +static const std::string bytes_to_string(const byte_vector_t &bytes){ +    std::string out; +    BOOST_FOREACH(boost::uint8_t byte, bytes){ +        if (byte < 32 or byte > 127) return out; +        out += byte; +    } +    return out; +} + +//! create a byte vector from a string, null terminate unless max length +static const byte_vector_t string_to_bytes(const std::string &string, size_t max_length){ +    byte_vector_t bytes; +    for (size_t i = 0; i < std::min(string.size(), max_length); i++){ +        bytes.push_back(string[i]); +    } +    if (bytes.size() < max_length - 1) bytes.push_back('\0'); +    return bytes; +} + +//////////////////////////////////////////////////////////////////////// +// format of daughterboard EEPROM +// 00: 0xDB code for ``I'm a daughterboard'' +// 01:   .. Daughterboard ID (LSB) +// 02:   .. Daughterboard ID (MSB) +// 03:   .. io bits  7-0 direction (bit set if it's an output from m'board) +// 04:   .. io bits 15-8 direction (bit set if it's an output from m'board) +// 05:   .. ADC0 DC offset correction (LSB) +// 06:   .. ADC0 DC offset correction (MSB) +// 07:   .. ADC1 DC offset correction (LSB) +// 08:   .. ADC1 DC offset correction (MSB) +//  ... +// 1f:   .. negative of the sum of bytes [0x00, 0x1e] + +#define DB_EEPROM_MAGIC         0x00 +#define DB_EEPROM_MAGIC_VALUE   0xDB +#define DB_EEPROM_ID_LSB        0x01 +#define DB_EEPROM_ID_MSB        0x02 +#define DB_EEPROM_REV_LSB       0x03 +#define DB_EEPROM_REV_MSB       0x04 +#define DB_EEPROM_OFFSET_0_LSB  0x05 // offset correction for ADC or DAC 0 +#define DB_EEPROM_OFFSET_0_MSB  0x06 +#define DB_EEPROM_OFFSET_1_LSB  0x07 // offset correction for ADC or DAC 1 +#define DB_EEPROM_OFFSET_1_MSB  0x08 +#define DB_EEPROM_SERIAL        0x09 +#define DB_EEPROM_SERIAL_LEN    0x09 //9 ASCII characters +#define DB_EEPROM_CHKSUM        0x1f + +#define DB_EEPROM_CLEN          0x20 // length of common portion of eeprom + +#define DB_EEPROM_CUSTOM_BASE   DB_EEPROM_CLEN // first avail offset for +                                               //   daughterboard specific use +//////////////////////////////////////////////////////////////////////// + +//negative sum of bytes excluding checksum byte +static boost::uint8_t checksum(const byte_vector_t &bytes){ +    int sum = 0; +    for (size_t i = 0; i < std::min(bytes.size(), size_t(DB_EEPROM_CHKSUM)); i++){ +        sum -= int(bytes.at(i)); +    } +    UHD_LOGV(often) << boost::format("sum: 0x%02x") % sum << std::endl; +    return boost::uint8_t(sum); +} + +dboard_eeprom_t::dboard_eeprom_t(void){ +    id = dboard_id_t::none(); +    serial = ""; +} + +void dboard_eeprom_t::load(i2c_iface &iface, boost::uint8_t addr){ +    byte_vector_t bytes = iface.read_eeprom(addr, 0, DB_EEPROM_CLEN); + +    std::ostringstream ss; +    for (size_t i = 0; i < bytes.size(); i++){ +        ss << boost::format( +            "eeprom byte[0x%02x] = 0x%02x") % i % int(bytes.at(i) +        ) << std::endl; +    } +    UHD_LOGV(often) << ss.str() << std::endl; + +    try{ +        UHD_ASSERT_THROW(bytes.size() >= DB_EEPROM_CLEN); +        UHD_ASSERT_THROW(bytes[DB_EEPROM_MAGIC] == DB_EEPROM_MAGIC_VALUE); +        UHD_ASSERT_THROW(bytes[DB_EEPROM_CHKSUM] == checksum(bytes)); + +        //parse the ids +        id = dboard_id_t::from_uint16(0 +            | (boost::uint16_t(bytes[DB_EEPROM_ID_LSB]) << 0) +            | (boost::uint16_t(bytes[DB_EEPROM_ID_MSB]) << 8) +        ); + +        //parse the serial +        serial = bytes_to_string( +            byte_vector_t(&bytes.at(DB_EEPROM_SERIAL), +            &bytes.at(DB_EEPROM_SERIAL+DB_EEPROM_SERIAL_LEN)) +        ); + +        //parse the revision +        const boost::uint16_t rev_num = 0 +            | (boost::uint16_t(bytes[DB_EEPROM_REV_LSB]) << 0) +            | (boost::uint16_t(bytes[DB_EEPROM_REV_MSB]) << 8) +        ; +        if (rev_num != 0 and rev_num != 0xffff){ +            revision = boost::lexical_cast<std::string>(rev_num); +        } + +    }catch(const uhd::assertion_error &){ +        id = dboard_id_t::none(); +        serial = ""; +    } +} + +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; + +    //load the id bytes +    bytes[DB_EEPROM_ID_LSB] = boost::uint8_t(id.to_uint16() >> 0); +    bytes[DB_EEPROM_ID_MSB] = boost::uint8_t(id.to_uint16() >> 8); + +    //load the serial bytes +    byte_vector_t ser_bytes = string_to_bytes(serial, DB_EEPROM_SERIAL_LEN); +    std::copy(ser_bytes.begin(), ser_bytes.end(), &bytes.at(DB_EEPROM_SERIAL)); + +    //load the revision bytes +    if (not revision.empty()){ +        const boost::uint16_t rev_num = boost::lexical_cast<boost::uint16_t>(revision); +        bytes[DB_EEPROM_REV_LSB] = boost::uint8_t(rev_num >> 0); +        bytes[DB_EEPROM_REV_MSB] = boost::uint8_t(rev_num >> 8); +    } + +    //load the checksum +    bytes[DB_EEPROM_CHKSUM] = checksum(bytes); + +    iface.write_eeprom(addr, 0, bytes); +} diff --git a/host/lib/usrp/dboard_id.cpp b/host/lib/usrp/dboard_id.cpp new file mode 100644 index 000000000..3028d2a3b --- /dev/null +++ b/host/lib/usrp/dboard_id.cpp @@ -0,0 +1,68 @@ +// +// Copyright 2010 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/dboard_id.hpp> +#include <boost/lexical_cast.hpp> +#include <boost/format.hpp> +#include <sstream> +#include <iostream> + +using namespace uhd::usrp; + +dboard_id_t::dboard_id_t(boost::uint16_t id){ +    _id = id; +} + +dboard_id_t dboard_id_t::none(void){ +    return dboard_id_t(); +} + +dboard_id_t dboard_id_t::from_uint16(boost::uint16_t uint16){ +    return dboard_id_t(uint16); +} + +boost::uint16_t dboard_id_t::to_uint16(void) const{ +    return _id; +} + +//used with lexical cast to parse a hex string +template <class T> struct to_hex{ +    T value; +    operator T() const {return value;} +    friend std::istream& operator>>(std::istream& in, to_hex& out){ +        in >> std::hex >> out.value; +        return in; +    } +}; + +dboard_id_t dboard_id_t::from_string(const std::string &string){ +    if (string.substr(0, 2) == "0x"){ +        return dboard_id_t::from_uint16(boost::lexical_cast<to_hex<boost::uint16_t> >(string)); +    } +    return dboard_id_t::from_uint16(boost::lexical_cast<boost::uint16_t>(string)); +} + +std::string dboard_id_t::to_string(void) const{ +    return str(boost::format("0x%04x") % this->to_uint16()); +} + +//Note: to_pp_string is implemented in the dboard manager +//because it needs access to the dboard registration table + +bool uhd::usrp::operator==(const dboard_id_t &lhs, const dboard_id_t &rhs){ +    return lhs.to_uint16() == rhs.to_uint16(); +} diff --git a/host/lib/usrp/dboard_iface.cpp b/host/lib/usrp/dboard_iface.cpp new file mode 100644 index 000000000..5cc5ea470 --- /dev/null +++ b/host/lib/usrp/dboard_iface.cpp @@ -0,0 +1,78 @@ +// +// Copyright 2010 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/dboard_iface.hpp> +#include <uhd/types/dict.hpp> + +using namespace uhd::usrp; + +struct dboard_iface::impl{ +    uhd::dict<unit_t, boost::uint16_t> pin_ctrl_shadow; +    uhd::dict<unit_t, uhd::dict<atr_reg_t, boost::uint16_t> > atr_reg_shadow; +    uhd::dict<unit_t, boost::uint16_t> gpio_ddr_shadow; +    uhd::dict<unit_t, boost::uint16_t> gpio_out_shadow; +}; + +dboard_iface::dboard_iface(void){ +    _impl = UHD_PIMPL_MAKE(impl, ()); +} + +template <typename T> +static T shadow_it(T &shadow, const T &value, const T &mask){ +    shadow = (shadow & ~mask) | (value & mask); +    return shadow; +} + +void dboard_iface::set_pin_ctrl( +    unit_t unit, boost::uint16_t value, boost::uint16_t mask +){ +    _set_pin_ctrl(unit, shadow_it(_impl->pin_ctrl_shadow[unit], value, mask)); +} + +boost::uint16_t dboard_iface::get_pin_ctrl(unit_t unit){ +    return _impl->pin_ctrl_shadow[unit]; +} + +void dboard_iface::set_atr_reg( +    unit_t unit, atr_reg_t reg, boost::uint16_t value, boost::uint16_t mask +){ +    _set_atr_reg(unit, reg, shadow_it(_impl->atr_reg_shadow[unit][reg], value, mask)); +} + +boost::uint16_t dboard_iface::get_atr_reg(unit_t unit, atr_reg_t reg){ +    return _impl->atr_reg_shadow[unit][reg]; +} + +void dboard_iface::set_gpio_ddr( +    unit_t unit, boost::uint16_t value, boost::uint16_t mask +){ +    _set_gpio_ddr(unit, shadow_it(_impl->gpio_ddr_shadow[unit], value, mask)); +} + +boost::uint16_t dboard_iface::get_gpio_ddr(unit_t unit){ +    return _impl->gpio_ddr_shadow[unit]; +} + +void dboard_iface::set_gpio_out( +    unit_t unit, boost::uint16_t value, boost::uint16_t mask +){ +    _set_gpio_out(unit, shadow_it(_impl->gpio_out_shadow[unit], value, mask)); +} + +boost::uint16_t dboard_iface::get_gpio_out(unit_t unit){ +    return _impl->gpio_out_shadow[unit]; +} diff --git a/host/lib/usrp/dboard_manager.cpp b/host/lib/usrp/dboard_manager.cpp new file mode 100644 index 000000000..340c1d3f9 --- /dev/null +++ b/host/lib/usrp/dboard_manager.cpp @@ -0,0 +1,332 @@ +// +// 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 "dboard_ctor_args.hpp" +#include <uhd/usrp/dboard_manager.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp> +#include <uhd/utils/safe_call.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/exception.hpp> +#include <uhd/types/dict.hpp> +#include <boost/tuple/tuple.hpp> +#include <boost/format.hpp> +#include <boost/bind.hpp> +#include <boost/foreach.hpp> +#include <boost/assign/list_of.hpp> + +using namespace uhd; +using namespace uhd::usrp; + +/*********************************************************************** + * dboard key class to use for look-up + **********************************************************************/ +class dboard_key_t{ +public: +    dboard_key_t(const dboard_id_t &id = dboard_id_t::none()): +        _rx_id(id), _tx_id(id), _xcvr(false){} + +    dboard_key_t(const dboard_id_t &rx_id, const dboard_id_t &tx_id): +        _rx_id(rx_id), _tx_id(tx_id), _xcvr(true){} + +    dboard_id_t xx_id(void) const{ +        UHD_ASSERT_THROW(not this->is_xcvr()); +        return this->_rx_id; +    } + +    dboard_id_t rx_id(void) const{ +        UHD_ASSERT_THROW(this->is_xcvr()); +        return this->_rx_id; +    } + +    dboard_id_t tx_id(void) const{ +        UHD_ASSERT_THROW(this->is_xcvr()); +        return this->_tx_id; +    } + +    bool is_xcvr(void) const{ +        return this->_xcvr; +    } + +private: +    dboard_id_t _rx_id, _tx_id; +    bool _xcvr; +}; + +bool operator==(const dboard_key_t &lhs, const dboard_key_t &rhs){ +    if (lhs.is_xcvr() and rhs.is_xcvr()) +        return lhs.rx_id() == rhs.rx_id() and lhs.tx_id() == rhs.tx_id(); +    if (not lhs.is_xcvr() and not rhs.is_xcvr()) +        return lhs.xx_id() == rhs.xx_id(); +    return false; +} + +/*********************************************************************** + * storage and registering for dboards + **********************************************************************/ +//dboard registry tuple: dboard constructor, canonical name, subdev names +typedef boost::tuple<dboard_manager::dboard_ctor_t, std::string, std::vector<std::string> > args_t; + +//map a dboard id to a dboard constructor +typedef uhd::dict<dboard_key_t, args_t> id_to_args_map_t; +UHD_SINGLETON_FCN(id_to_args_map_t, get_id_to_args_map) + +static void register_dboard_key( +    const dboard_key_t &dboard_key, +    dboard_manager::dboard_ctor_t dboard_ctor, +    const std::string &name, +    const std::vector<std::string> &subdev_names +){ +    UHD_LOGV(always) << "registering: " << name << std::endl; +    if (get_id_to_args_map().has_key(dboard_key)){ + +        if (dboard_key.is_xcvr()) throw uhd::key_error(str(boost::format( +            "The dboard id pair [%s, %s] is already registered to %s." +        ) % dboard_key.rx_id().to_string() % dboard_key.tx_id().to_string() % get_id_to_args_map()[dboard_key].get<1>())); + +        else throw uhd::key_error(str(boost::format( +            "The dboard id %s is already registered to %s." +        ) % dboard_key.xx_id().to_string() % get_id_to_args_map()[dboard_key].get<1>())); + +    } +    get_id_to_args_map()[dboard_key] = args_t(dboard_ctor, name, subdev_names); +} + +void dboard_manager::register_dboard( +    const dboard_id_t &dboard_id, +    dboard_ctor_t dboard_ctor, +    const std::string &name, +    const std::vector<std::string> &subdev_names +){ +    register_dboard_key(dboard_key_t(dboard_id), dboard_ctor, name, subdev_names); +} + +void dboard_manager::register_dboard( +    const dboard_id_t &rx_dboard_id, +    const dboard_id_t &tx_dboard_id, +    dboard_ctor_t dboard_ctor, +    const std::string &name, +    const std::vector<std::string> &subdev_names +){ +    register_dboard_key(dboard_key_t(rx_dboard_id, tx_dboard_id), dboard_ctor, name, subdev_names); +} + +std::string dboard_id_t::to_cname(void) const{ +    std::string cname; +    BOOST_FOREACH(const dboard_key_t &key, get_id_to_args_map().keys()){ +        if ( +            (not key.is_xcvr() and *this == key.xx_id()) or +            (key.is_xcvr() and (*this == key.rx_id() or *this == key.tx_id())) +        ){ +            if (not cname.empty()) cname += ", "; +            cname += get_id_to_args_map()[key].get<1>(); +        } +    } +    return (cname.empty())? "Unknown" : cname; +} + +std::string dboard_id_t::to_pp_string(void) const{ +    return str(boost::format("%s (%s)") % this->to_cname() % this->to_string()); +} + +/*********************************************************************** + * dboard manager implementation class + **********************************************************************/ +class dboard_manager_impl : public dboard_manager{ + +public: +    dboard_manager_impl( +        dboard_id_t rx_dboard_id, +        dboard_id_t tx_dboard_id, +        dboard_iface::sptr iface, +        property_tree::sptr subtree +    ); +    ~dboard_manager_impl(void); + +private: +    void init(dboard_id_t, dboard_id_t, property_tree::sptr); +    //list of rx and tx dboards in this dboard_manager +    //each dboard here is actually a subdevice proxy +    //the subdevice proxy is internal to the cpp file +    uhd::dict<std::string, dboard_base::sptr> _rx_dboards; +    uhd::dict<std::string, dboard_base::sptr> _tx_dboards; +    dboard_iface::sptr _iface; +    void set_nice_dboard_if(void); +}; + +/*********************************************************************** + * make routine for dboard manager + **********************************************************************/ +dboard_manager::sptr dboard_manager::make( +    dboard_id_t rx_dboard_id, +    dboard_id_t tx_dboard_id, +    dboard_id_t gdboard_id, +    dboard_iface::sptr iface, +    property_tree::sptr subtree +){ +    return dboard_manager::sptr( +        new dboard_manager_impl( +            rx_dboard_id, +            (gdboard_id == dboard_id_t::none())? tx_dboard_id : gdboard_id, +            iface, subtree +        ) +    ); +} + +/*********************************************************************** + * implementation class methods + **********************************************************************/ +dboard_manager_impl::dboard_manager_impl( +    dboard_id_t rx_dboard_id, +    dboard_id_t tx_dboard_id, +    dboard_iface::sptr iface, +    property_tree::sptr subtree +): +    _iface(iface) +{ +    try{ +        this->init(rx_dboard_id, tx_dboard_id, subtree); +    } +    catch(const std::exception &e){ +        UHD_MSG(error) << boost::format( +            "The daughterboard manager encountered a recoverable error in init.\n" +            "Loading the \"unknown\" daughterboard implementations to continue.\n" +            "The daughterboard cannot operate until this error is resolved.\n" +        ) << e.what() << std::endl; +        //clean up the stuff added by the call above +        if (subtree->exists("rx_frontends")) subtree->remove("rx_frontends"); +        if (subtree->exists("tx_frontends")) subtree->remove("tx_frontends"); +        this->init(dboard_id_t::none(), dboard_id_t::none(), subtree); +    } +} + +void dboard_manager_impl::init( +    dboard_id_t rx_dboard_id, dboard_id_t tx_dboard_id, property_tree::sptr subtree +){ +    //find the dboard key matches for the dboard ids +    dboard_key_t rx_dboard_key, tx_dboard_key, xcvr_dboard_key; +    BOOST_FOREACH(const dboard_key_t &key, get_id_to_args_map().keys()){ +        if (key.is_xcvr()){ +            if (rx_dboard_id == key.rx_id() and tx_dboard_id == key.tx_id()) xcvr_dboard_key = key; +            if (rx_dboard_id == key.rx_id()) rx_dboard_key = key; //kept to handle warning +            if (tx_dboard_id == key.tx_id()) tx_dboard_key = key; //kept to handle warning +        } +        else{ +            if (rx_dboard_id == key.xx_id()) rx_dboard_key = key; +            if (tx_dboard_id == key.xx_id()) tx_dboard_key = key; +        } +    } + +    //warn for invalid dboard id xcvr combinations +    if (not xcvr_dboard_key.is_xcvr() and (rx_dboard_key.is_xcvr() or tx_dboard_key.is_xcvr())){ +        UHD_MSG(warning) << boost::format( +            "Unknown transceiver board ID combination.\n" +            "Is your daughter-board mounted properly?\n" +            "RX dboard ID: %s\n" +            "TX dboard ID: %s\n" +        ) % rx_dboard_id.to_pp_string() % tx_dboard_id.to_pp_string(); +    } + +    //initialize the gpio pins before creating subdevs +    set_nice_dboard_if(); + +    //dboard constructor args +    dboard_ctor_args_t db_ctor_args; +    db_ctor_args.db_iface = _iface; + +    //make xcvr subdevs +    if (xcvr_dboard_key.is_xcvr()){ + +        //extract data for the xcvr dboard key +        dboard_ctor_t dboard_ctor; std::string name; std::vector<std::string> subdevs; +        boost::tie(dboard_ctor, name, subdevs) = get_id_to_args_map()[xcvr_dboard_key]; + +        //create the xcvr object for each subdevice +        BOOST_FOREACH(const std::string &subdev, subdevs){ +            db_ctor_args.sd_name = subdev; +            db_ctor_args.rx_id = rx_dboard_id; +            db_ctor_args.tx_id = tx_dboard_id; +            db_ctor_args.rx_subtree = subtree->subtree("rx_frontends/" + subdev); +            db_ctor_args.tx_subtree = subtree->subtree("tx_frontends/" + subdev); +            dboard_base::sptr xcvr_dboard = dboard_ctor(&db_ctor_args); +            _rx_dboards[subdev] = xcvr_dboard; +            _tx_dboards[subdev] = xcvr_dboard; +        } +    } + +    //make tx and rx subdevs (separate subdevs for rx and tx dboards) +    else{ + +        //force the rx key to the unknown board for bad combinations +        if (rx_dboard_key.is_xcvr() or rx_dboard_key.xx_id() == dboard_id_t::none()){ +            rx_dboard_key = dboard_key_t(0xfff1); +        } + +        //extract data for the rx dboard key +        dboard_ctor_t rx_dboard_ctor; std::string rx_name; std::vector<std::string> rx_subdevs; +        boost::tie(rx_dboard_ctor, rx_name, rx_subdevs) = get_id_to_args_map()[rx_dboard_key]; + +        //make the rx subdevs +        BOOST_FOREACH(const std::string &subdev, rx_subdevs){ +            db_ctor_args.sd_name = subdev; +            db_ctor_args.rx_id = rx_dboard_id; +            db_ctor_args.tx_id = dboard_id_t::none(); +            db_ctor_args.rx_subtree = subtree->subtree("rx_frontends/" + subdev); +            db_ctor_args.tx_subtree = property_tree::sptr(); //null +            _rx_dboards[subdev] = rx_dboard_ctor(&db_ctor_args); +        } + +        //force the tx key to the unknown board for bad combinations +        if (tx_dboard_key.is_xcvr() or tx_dboard_key.xx_id() == dboard_id_t::none()){ +            tx_dboard_key = dboard_key_t(0xfff0); +        } + +        //extract data for the tx dboard key +        dboard_ctor_t tx_dboard_ctor; std::string tx_name; std::vector<std::string> tx_subdevs; +        boost::tie(tx_dboard_ctor, tx_name, tx_subdevs) = get_id_to_args_map()[tx_dboard_key]; + +        //make the tx subdevs +        BOOST_FOREACH(const std::string &subdev, tx_subdevs){ +            db_ctor_args.sd_name = subdev; +            db_ctor_args.rx_id = dboard_id_t::none(); +            db_ctor_args.tx_id = tx_dboard_id; +            db_ctor_args.rx_subtree = property_tree::sptr(); //null +            db_ctor_args.tx_subtree = subtree->subtree("tx_frontends/" + subdev); +            _tx_dboards[subdev] = tx_dboard_ctor(&db_ctor_args); +        } +    } +} + +dboard_manager_impl::~dboard_manager_impl(void){UHD_SAFE_CALL( +    set_nice_dboard_if(); +)} + +void dboard_manager_impl::set_nice_dboard_if(void){ +    //make a list of possible unit types +    std::vector<dboard_iface::unit_t> units = boost::assign::list_of +        (dboard_iface::UNIT_RX) +        (dboard_iface::UNIT_TX) +    ; + +    //set nice settings on each unit +    BOOST_FOREACH(dboard_iface::unit_t unit, units){ +        _iface->set_gpio_ddr(unit, 0x0000); //all inputs +        _iface->set_gpio_out(unit, 0x0000); //all low +        _iface->set_pin_ctrl(unit, 0x0000); //all gpio +        _iface->set_clock_enabled(unit, false); //clock off +    } +} diff --git a/host/lib/usrp/e100/CMakeLists.txt b/host/lib/usrp/e100/CMakeLists.txt new file mode 100644 index 000000000..ac9d8c655 --- /dev/null +++ b/host/lib/usrp/e100/CMakeLists.txt @@ -0,0 +1,40 @@ +# +# 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/>. +# + +######################################################################## +# This file included, use CMake directory variables +######################################################################## + +######################################################################## +# Conditionally configure the USRP-E100 support +######################################################################## +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}/codec_ctrl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/dboard_iface.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/e100_ctrl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/e100_impl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/e100_mmap_zero_copy.cpp +        ${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 new file mode 100644 index 000000000..9e355ce17 --- /dev/null +++ b/host/lib/usrp/e100/clock_ctrl.cpp @@ -0,0 +1,538 @@ +// +// 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 "ad9522_regs.hpp" +#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp> +#include <uhd/utils/assert_has.hpp> +#include <boost/cstdint.hpp> +#include "e100_regs.hpp" //spi slave constants +#include <boost/assign/list_of.hpp> +#include <boost/foreach.hpp> +#include <boost/format.hpp> +#include <boost/thread/thread.hpp> +#include <boost/math/common_factor_rt.hpp> //gcd +#include <algorithm> +#include <utility> + +using namespace uhd; + +/*********************************************************************** + * Constants + **********************************************************************/ +static const bool ENABLE_THE_TEST_OUT = true; +static const double REFERENCE_INPUT_RATE = 10e6; + +/*********************************************************************** + * Helpers + **********************************************************************/ +template <typename div_type, typename bypass_type> static void set_clock_divider( +    size_t divider, div_type &low, div_type &high, bypass_type &bypass +){ +    high = divider/2 - 1; +    low = divider - high - 2; +    bypass = (divider == 1)? 1 : 0; +} + +/*********************************************************************** + * Clock rate calculation stuff: + *   Using the internal VCO between 1400 and 1800 MHz + **********************************************************************/ +struct clock_settings_type{ +    size_t ref_clock_doubler, r_counter, a_counter, b_counter, prescaler, vco_divider, chan_divider; +    size_t get_n_counter(void) const{return prescaler * b_counter + a_counter;} +    double get_ref_rate(void) const{return REFERENCE_INPUT_RATE * ref_clock_doubler;} +    double get_vco_rate(void) const{return get_ref_rate()/r_counter * get_n_counter();} +    double get_chan_rate(void) const{return get_vco_rate()/vco_divider;} +    double get_out_rate(void) const{return get_chan_rate()/chan_divider;} +    std::string to_pp_string(void) const{ +        return str(boost::format( +            "  r_counter: %d\n" +            "  a_counter: %d\n" +            "  b_counter: %d\n" +            "  prescaler: %d\n" +            "  vco_divider: %d\n" +            "  chan_divider: %d\n" +            "  vco_rate: %fMHz\n" +            "  chan_rate: %fMHz\n" +            "  out_rate: %fMHz\n" +            ) +            % r_counter +            % a_counter +            % b_counter +            % prescaler +            % vco_divider +            % chan_divider +            % (get_vco_rate()/1e6) +            % (get_chan_rate()/1e6) +            % (get_out_rate()/1e6) +        ); +    } +}; + +//! gives the greatest divisor of num between 1 and max inclusive +template<typename T> static inline T greatest_divisor(T num, T max){ +    for (T i = max; i > 1; i--) if (num%i == 0) return i; return 1; +} + +//! gives the least divisor of num between min and num exclusive +template<typename T> static inline T least_divisor(T num, T min){ +    for (T i = min; i < num; i++) if (num%i == 0) return i; return 1; +} + +static clock_settings_type get_clock_settings(double rate){ +    clock_settings_type cs; +    cs.ref_clock_doubler = 2; //always doubling +    cs.prescaler = 8; //set to 8 when input is under 2400 MHz + +    //basic formulas used below: +    //out_rate*X = ref_rate*Y +    //X = i*ref_rate/gcd +    //Y = i*out_rate/gcd +    //X = chan_div * vco_div * R +    //Y = P*B + A + +    const boost::uint64_t out_rate = boost::uint64_t(rate); +    const boost::uint64_t ref_rate = boost::uint64_t(cs.get_ref_rate()); +    const size_t gcd = size_t(boost::math::gcd(ref_rate, out_rate)); + +    for (size_t i = 1; i <= 100; i++){ +        const size_t X = i*ref_rate/gcd; +        const size_t Y = i*out_rate/gcd; + +        //determine A and B (P is fixed) +        cs.b_counter = Y/cs.prescaler; +        cs.a_counter = Y - cs.b_counter*cs.prescaler; + +        static const double vco_bound_pad = 100e6; +        for ( //calculate an r divider that fits into the bounds of the vco +            cs.r_counter  = size_t(cs.get_n_counter()*cs.get_ref_rate()/(1800e6 - vco_bound_pad)); +            cs.r_counter <= size_t(cs.get_n_counter()*cs.get_ref_rate()/(1400e6 + vco_bound_pad)) +            and cs.r_counter > 0; cs.r_counter++ +        ){ + +            //determine chan_div and vco_div +            //and fill in that order of preference +            cs.chan_divider = greatest_divisor<size_t>(X/cs.r_counter, 32); +            cs.vco_divider = greatest_divisor<size_t>(X/cs.chan_divider/cs.r_counter, 6); + +            //avoid a vco divider of 1 (if possible) +            if (cs.vco_divider == 1){ +                cs.vco_divider = least_divisor<size_t>(cs.chan_divider, 2); +                cs.chan_divider /= cs.vco_divider; +            } + +            UHD_LOGV(always) +                << "gcd " << gcd << std::endl +                << "X " << X << std::endl +                << "Y " << Y << std::endl +                << cs.to_pp_string() << std::endl +            ; + +            //filter limits on the counters +            if (cs.vco_divider == 1) continue; +            if (cs.r_counter >= (1<<14)) continue; +            if (cs.b_counter == 2) continue; +            if (cs.b_counter == 1 and cs.a_counter != 0) continue; +            if (cs.b_counter >= (1<<13)) continue; +            if (cs.a_counter >= (1<<6)) continue; +            if (cs.get_vco_rate() > 1800e6 - vco_bound_pad) continue; +            if (cs.get_vco_rate() < 1400e6 + vco_bound_pad) continue; +            if (cs.get_out_rate() != rate) continue; + +            UHD_MSG(status) << "USRP-E100 clock control: " << i << std::endl << cs.to_pp_string() << std::endl; +            return cs; +        } +    } + +    throw uhd::value_error(str(boost::format( +        "USRP-E100 clock control: could not calculate settings for clock rate %fMHz" +    ) % (rate/1e6))); +} + +/*********************************************************************** + * Clock Control Implementation + **********************************************************************/ +class e100_clock_ctrl_impl : public e100_clock_ctrl{ +public: +    e100_clock_ctrl_impl(spi_iface::sptr iface, double master_clock_rate, const bool dboard_clocks_diff): +        _dboard_clocks_diff(dboard_clocks_diff) +    { +        _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 +        //Note: out0 should already be clocking the FPGA or this isnt going to work +        _ad9522_regs.sdo_active = ad9522_regs_t::SDO_ACTIVE_SDO_SDIO; +        _ad9522_regs.enb_stat_eeprom_at_stat_pin = 0; //use status pin +        _ad9522_regs.status_pin_control = 0x1; //n divider +        _ad9522_regs.ld_pin_control = 0x00; //dld +        _ad9522_regs.refmon_pin_control = 0x12; //show ref2 +        _ad9522_regs.lock_detect_counter = ad9522_regs_t::LOCK_DETECT_COUNTER_16CYC; + +        this->use_internal_ref(); + +        //initialize the FPGA clock rate +        UHD_MSG(status) << boost::format("Initializing FPGA clock to %fMHz...") % (master_clock_rate/1e6) << std::endl; +        this->set_fpga_clock_rate(master_clock_rate); + +        this->enable_test_clock(ENABLE_THE_TEST_OUT); +        this->enable_rx_dboard_clock(false); +        this->enable_tx_dboard_clock(false); +    } + +    ~e100_clock_ctrl_impl(void){ +        this->enable_test_clock(ENABLE_THE_TEST_OUT); +        this->enable_rx_dboard_clock(false); +        this->enable_tx_dboard_clock(false); +    } + +    /*********************************************************************** +     * Clock rate control: +     *  - set clock rate w/ internal VCO +     *  - set clock rate w/ external VCXO +     **********************************************************************/ +    void set_clock_settings_with_internal_vco(double rate){ +        const clock_settings_type cs = get_clock_settings(rate); + +        //set the rates to private variables so the implementation knows! +        _chan_rate = cs.get_chan_rate(); +        _out_rate = cs.get_out_rate(); + +        _ad9522_regs.enable_clock_doubler = (cs.ref_clock_doubler == 2)? 1 : 0; + +        _ad9522_regs.set_r_counter(cs.r_counter); +        _ad9522_regs.a_counter = cs.a_counter; +        _ad9522_regs.set_b_counter(cs.b_counter); +        UHD_ASSERT_THROW(cs.prescaler == 8); //assumes this below: +        _ad9522_regs.prescaler_p = ad9522_regs_t::PRESCALER_P_DIV8_9; + +        _ad9522_regs.pll_power_down = ad9522_regs_t::PLL_POWER_DOWN_NORMAL; +        _ad9522_regs.cp_current = ad9522_regs_t::CP_CURRENT_1_2MA; + +        _ad9522_regs.bypass_vco_divider = 0; +        switch(cs.vco_divider){ +        case 1: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV1; break; +        case 2: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV2; break; +        case 3: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV3; break; +        case 4: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV4; break; +        case 5: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV5; break; +        case 6: _ad9522_regs.vco_divider = ad9522_regs_t::VCO_DIVIDER_DIV6; break; +        } +        _ad9522_regs.select_vco_or_clock = ad9522_regs_t::SELECT_VCO_OR_CLOCK_VCO; + +        //setup fpga master clock +        _ad9522_regs.out0_format = ad9522_regs_t::OUT0_FORMAT_LVDS; +        set_clock_divider(cs.chan_divider, +            _ad9522_regs.divider0_low_cycles, +            _ad9522_regs.divider0_high_cycles, +            _ad9522_regs.divider0_bypass +        ); + +        //setup codec clock +        _ad9522_regs.out3_format = ad9522_regs_t::OUT3_FORMAT_LVDS; +        set_clock_divider(cs.chan_divider, +            _ad9522_regs.divider1_low_cycles, +            _ad9522_regs.divider1_high_cycles, +            _ad9522_regs.divider1_bypass +        ); + +        this->send_all_regs(); +        calibrate_now(); +    } + +    void set_clock_settings_with_external_vcxo(double rate){ +        //set the rates to private variables so the implementation knows! +        _chan_rate = rate; +        _out_rate = rate; + +        _ad9522_regs.enable_clock_doubler = 1; //doubler always on +        const double ref_rate = REFERENCE_INPUT_RATE*2; + +        //bypass prescaler such that N = B +        long gcd = boost::math::gcd(long(ref_rate), long(rate)); +        _ad9522_regs.set_r_counter(int(ref_rate/gcd)); +        _ad9522_regs.a_counter = 0; +        _ad9522_regs.set_b_counter(int(rate/gcd)); +        _ad9522_regs.prescaler_p = ad9522_regs_t::PRESCALER_P_DIV1; + +        //setup external vcxo +        _ad9522_regs.pll_power_down = ad9522_regs_t::PLL_POWER_DOWN_NORMAL; +        _ad9522_regs.cp_current = ad9522_regs_t::CP_CURRENT_1_2MA; +        _ad9522_regs.bypass_vco_divider = 1; +        _ad9522_regs.select_vco_or_clock = ad9522_regs_t::SELECT_VCO_OR_CLOCK_EXTERNAL; + +        //setup fpga master clock +        _ad9522_regs.out0_format = ad9522_regs_t::OUT0_FORMAT_LVDS; +        _ad9522_regs.divider0_bypass = 1; + +        //setup codec clock +        _ad9522_regs.out3_format = ad9522_regs_t::OUT3_FORMAT_LVDS; +        _ad9522_regs.divider1_bypass = 1; + +        this->send_all_regs(); +    } + +    void set_fpga_clock_rate(double rate){ +        if (_out_rate == rate) return; +        if (rate == 61.44e6) set_clock_settings_with_external_vcxo(rate); +        else                 set_clock_settings_with_internal_vco(rate); +        set_rx_dboard_clock_rate(rate); +        set_tx_dboard_clock_rate(rate); +    } + +    double get_fpga_clock_rate(void){ +        return this->_out_rate; +    } + +    /*********************************************************************** +     * Special test clock output +     **********************************************************************/ +    void enable_test_clock(bool enb){ +        //setup test clock (same divider as codec clock) +        _ad9522_regs.out4_format = ad9522_regs_t::OUT4_FORMAT_CMOS; +        _ad9522_regs.out4_cmos_configuration = (enb)? +            ad9522_regs_t::OUT4_CMOS_CONFIGURATION_A_ON : +            ad9522_regs_t::OUT4_CMOS_CONFIGURATION_OFF; +        this->send_reg(0x0F4); +        this->latch_regs(); +    } + +    /*********************************************************************** +     * RX Dboard Clock Control (output 9, divider 3) +     **********************************************************************/ +    void enable_rx_dboard_clock(bool enb){ +        if (_dboard_clocks_diff){ +            _ad9522_regs.out9_format = ad9522_regs_t::OUT9_FORMAT_LVDS; +            _ad9522_regs.out9_lvds_power_down = enb? 0 : 1; +        } +        else{ +            _ad9522_regs.out9_format = ad9522_regs_t::OUT9_FORMAT_CMOS; +            _ad9522_regs.out9_cmos_configuration = (enb)? +                ad9522_regs_t::OUT9_CMOS_CONFIGURATION_B_ON : +                ad9522_regs_t::OUT9_CMOS_CONFIGURATION_OFF; +        } +        this->send_reg(0x0F9); +        this->latch_regs(); +    } + +    std::vector<double> get_rx_dboard_clock_rates(void){ +        std::vector<double> rates; +        for(size_t div = 1; div <= 16+16; div++) +            rates.push_back(this->_chan_rate/div); +        return rates; +    } + +    void set_rx_dboard_clock_rate(double rate){ +        assert_has(get_rx_dboard_clock_rates(), rate, "rx dboard clock rate"); +        _rx_clock_rate = rate; +        size_t divider = size_t(this->_chan_rate/rate); +        //set the divider registers +        set_clock_divider(divider, +            _ad9522_regs.divider3_low_cycles, +            _ad9522_regs.divider3_high_cycles, +            _ad9522_regs.divider3_bypass +        ); +        this->send_reg(0x199); +        this->send_reg(0x19a); +        this->soft_sync(); +    } + +    double get_rx_clock_rate(void){ +        return _rx_clock_rate; +    } + +    /*********************************************************************** +     * TX Dboard Clock Control (output 6, divider 2) +     **********************************************************************/ +    void enable_tx_dboard_clock(bool enb){ +        if (_dboard_clocks_diff){ +            _ad9522_regs.out6_format = ad9522_regs_t::OUT6_FORMAT_LVDS; +            _ad9522_regs.out6_lvds_power_down = enb? 0 : 1; +        } +        else{ +            _ad9522_regs.out6_format = ad9522_regs_t::OUT6_FORMAT_CMOS; +            _ad9522_regs.out6_cmos_configuration = (enb)? +                ad9522_regs_t::OUT6_CMOS_CONFIGURATION_B_ON : +                ad9522_regs_t::OUT6_CMOS_CONFIGURATION_OFF; +        } +        this->send_reg(0x0F6); +        this->latch_regs(); +    } + +    std::vector<double> get_tx_dboard_clock_rates(void){ +        return get_rx_dboard_clock_rates(); //same master clock, same dividers... +    } + +    void set_tx_dboard_clock_rate(double rate){ +        assert_has(get_tx_dboard_clock_rates(), rate, "tx dboard clock rate"); +        _tx_clock_rate = rate; +        size_t divider = size_t(this->_chan_rate/rate); +        //set the divider registers +        set_clock_divider(divider, +            _ad9522_regs.divider2_low_cycles, +            _ad9522_regs.divider2_high_cycles, +            _ad9522_regs.divider2_bypass +        ); +        this->send_reg(0x196); +        this->send_reg(0x197); +        this->soft_sync(); +    } + +    double get_tx_clock_rate(void){ +        return _tx_clock_rate; +    } + +    /*********************************************************************** +     * Clock reference control +     **********************************************************************/ +    void use_internal_ref(void) { +        _ad9522_regs.enable_ref2 = 1; +        _ad9522_regs.enable_ref1 = 0; +        _ad9522_regs.select_ref = ad9522_regs_t::SELECT_REF_REF2; +        _ad9522_regs.enb_auto_ref_switchover = ad9522_regs_t::ENB_AUTO_REF_SWITCHOVER_MANUAL; +        this->send_reg(0x01C); +        this->latch_regs(); +    } +     +    void use_external_ref(void) { +        _ad9522_regs.enable_ref2 = 0; +        _ad9522_regs.enable_ref1 = 1; +        _ad9522_regs.select_ref = ad9522_regs_t::SELECT_REF_REF1; +        _ad9522_regs.enb_auto_ref_switchover = ad9522_regs_t::ENB_AUTO_REF_SWITCHOVER_MANUAL; +        this->send_reg(0x01C); +        this->latch_regs(); +    } +     +    void use_auto_ref(void) { +        _ad9522_regs.enable_ref2 = 1; +        _ad9522_regs.enable_ref1 = 1; +        _ad9522_regs.select_ref = ad9522_regs_t::SELECT_REF_REF1; +        _ad9522_regs.enb_auto_ref_switchover = ad9522_regs_t::ENB_AUTO_REF_SWITCHOVER_AUTO; +        this->send_reg(0x01C); +        this->latch_regs(); +    } + +    bool get_locked(void){ +        static const boost::uint8_t addr = 0x01F; +        boost::uint32_t reg = _iface->read_spi( +            UE_SPI_SS_AD9522, spi_config_t::EDGE_RISE, +            _ad9522_regs.get_read_reg(addr), 24 +        ); +        _ad9522_regs.set_reg(addr, reg); +        return _ad9522_regs.digital_lock_detect != 0; +    } + +private: +    spi_iface::sptr _iface; +    const bool _dboard_clocks_diff; +    ad9522_regs_t _ad9522_regs; +    double _out_rate; //rate at the fpga and codec +    double _chan_rate; //rate before final dividers +    double _rx_clock_rate, _tx_clock_rate; + +    void latch_regs(void){ +        _ad9522_regs.io_update = 1; +        this->send_reg(0x232); +    } + +    void send_reg(boost::uint16_t addr){ +        boost::uint32_t reg = _ad9522_regs.get_write_reg(addr); +        UHD_LOGV(often) << "clock control write reg: " << std::hex << reg << std::endl; +        _iface->write_spi( +            UE_SPI_SS_AD9522, +            spi_config_t::EDGE_RISE, +            reg, 24 +        ); +    } + +    void calibrate_now(void){ +        //vco calibration routine: +        _ad9522_regs.vco_calibration_now = 0; +        this->send_reg(0x18); +        this->latch_regs(); +        _ad9522_regs.vco_calibration_now = 1; +        this->send_reg(0x18); +        this->latch_regs(); +        //wait for calibration done: +        static const boost::uint8_t addr = 0x01F; +        for (size_t ms10 = 0; ms10 < 100; ms10++){ +            boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +            boost::uint32_t reg = _iface->read_spi( +                UE_SPI_SS_AD9522, spi_config_t::EDGE_RISE, +                _ad9522_regs.get_read_reg(addr), 24 +            ); +            _ad9522_regs.set_reg(addr, reg); +            if (_ad9522_regs.vco_calibration_finished) goto wait_for_ld; +        } +        UHD_MSG(error) << "USRP-E100 clock control: VCO calibration timeout" << std::endl; +        wait_for_ld: +        //wait for digital lock detect: +        for (size_t ms10 = 0; ms10 < 100; ms10++){ +            boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +            boost::uint32_t reg = _iface->read_spi( +                UE_SPI_SS_AD9522, spi_config_t::EDGE_RISE, +                _ad9522_regs.get_read_reg(addr), 24 +            ); +            _ad9522_regs.set_reg(addr, reg); +            if (_ad9522_regs.digital_lock_detect) return; +        } +        UHD_MSG(error) << "USRP-E100 clock control: lock detection timeout" << std::endl; +    } + +    void soft_sync(void){ +        _ad9522_regs.soft_sync = 1; +        this->send_reg(0x230); +        this->latch_regs(); +        _ad9522_regs.soft_sync = 0; +        this->send_reg(0x230); +        this->latch_regs(); +    } + +    void send_all_regs(void){ +        //setup a list of register ranges to write +        typedef std::pair<boost::uint16_t, boost::uint16_t> range_t; +        static const std::vector<range_t> ranges = boost::assign::list_of +            (range_t(0x000, 0x000)) (range_t(0x010, 0x01F)) +            (range_t(0x0F0, 0x0FD)) (range_t(0x190, 0x19B)) +            (range_t(0x1E0, 0x1E1)) (range_t(0x230, 0x230)) +        ; + +        //write initial register values and latch/update +        BOOST_FOREACH(const range_t &range, ranges){ +            for(boost::uint16_t addr = range.first; addr <= range.second; addr++){ +                this->send_reg(addr); +            } +        } +        this->latch_regs(); +    } +}; + +/*********************************************************************** + * Clock Control Make + **********************************************************************/ +e100_clock_ctrl::sptr e100_clock_ctrl::make(spi_iface::sptr iface, double master_clock_rate, const bool dboard_clocks_diff){ +    return sptr(new e100_clock_ctrl_impl(iface, master_clock_rate, dboard_clocks_diff)); +} diff --git a/host/lib/usrp/e100/clock_ctrl.hpp b/host/lib/usrp/e100/clock_ctrl.hpp new file mode 100644 index 000000000..803265556 --- /dev/null +++ b/host/lib/usrp/e100/clock_ctrl.hpp @@ -0,0 +1,127 @@ +// +// 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_USRP_E100_CLOCK_CTRL_HPP +#define INCLUDED_USRP_E100_CLOCK_CTRL_HPP + +#include <uhd/types/serial.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> +#include <vector> + +/*! + * The usrp-e clock control: + * - Setup system clocks. + * - Disable/enable clock lines. + */ +class e100_clock_ctrl : boost::noncopyable{ +public: +    typedef boost::shared_ptr<e100_clock_ctrl> sptr; + +    /*! +     * Make a new clock control object. +     * \param iface the spi iface object +     * \param master clock rate the FPGA rate +     * param dboard_clocks_diff are they differential? +     * \return the clock control object +     */ +    static sptr make(uhd::spi_iface::sptr iface, double master_clock_rate, const bool dboard_clocks_diff); + +    /*! +     * Set the rate of the fpga clock line. +     * Throws if rate is not valid. +     * \param rate the new rate in Hz +     */ +    virtual void set_fpga_clock_rate(double rate) = 0; + +    /*! +     * Get the rate of the fpga clock line. +     * \return the fpga clock rate in Hz +     */ +    virtual double get_fpga_clock_rate(void) = 0; + +    /*! +     * Get the possible rates of the rx dboard clock. +     * \return a vector of clock rates in Hz +     */ +    virtual std::vector<double> get_rx_dboard_clock_rates(void) = 0; + +    /*! +     * Get the possible rates of the tx dboard clock. +     * \return a vector of clock rates in Hz +     */ +    virtual std::vector<double> get_tx_dboard_clock_rates(void) = 0; + +    /*! +     * Set the rx dboard clock rate to a possible rate. +     * \param rate the new clock rate in Hz +     * \throw exception when rate cannot be achieved +     */ +    virtual void set_rx_dboard_clock_rate(double rate) = 0; + +    /*! +     * Set the tx dboard clock rate to a possible rate. +     * \param rate the new clock rate in Hz +     * \throw exception when rate cannot be achieved +     */ +    virtual void set_tx_dboard_clock_rate(double rate) = 0; + +    /*! +     * Get the current rx dboard clock rate. +     * \return the clock rate in Hz +     */ +    virtual double get_rx_clock_rate(void) = 0; + +    /*! +     * Get the current tx dboard clock rate. +     * \return the clock rate in Hz +     */ +    virtual double get_tx_clock_rate(void) = 0; + +    /*! +     * Enable/disable the rx dboard clock. +     * \param enb true to enable +     */ +    virtual void enable_rx_dboard_clock(bool enb) = 0; + +    /*! +     * Enable/disable the tx dboard clock. +     * \param enb true to enable +     */ +    virtual void enable_tx_dboard_clock(bool enb) = 0; +     +    /*! +     * Use the internal TCXO reference +     */ +    virtual void use_internal_ref(void) = 0; +     +    /*! +     * Use the external SMA reference +     */ +    virtual void use_external_ref(void) = 0; +     +    /*! +     * Use external if available, internal otherwise +     */ +    virtual void use_auto_ref(void) = 0; + +    //! Is the reference locked? +    virtual bool get_locked(void) = 0; + +}; + +#endif /* INCLUDED_USRP_E100_CLOCK_CTRL_HPP */ diff --git a/host/lib/usrp/e100/codec_ctrl.cpp b/host/lib/usrp/e100/codec_ctrl.cpp new file mode 100644 index 000000000..13b3bc951 --- /dev/null +++ b/host/lib/usrp/e100/codec_ctrl.cpp @@ -0,0 +1,288 @@ +// +// 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 "codec_ctrl.hpp" +#include "ad9862_regs.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/algorithm.hpp> +#include <boost/cstdint.hpp> +#include <boost/tuple/tuple.hpp> +#include <boost/math/special_functions/round.hpp> +#include "e100_regs.hpp" //spi slave constants +#include <boost/assign/list_of.hpp> + +using namespace uhd; + +const gain_range_t e100_codec_ctrl::tx_pga_gain_range(-20, 0, double(0.1)); +const gain_range_t e100_codec_ctrl::rx_pga_gain_range(0, 20, 1); + +/*********************************************************************** + * Codec Control Implementation + **********************************************************************/ +class e100_codec_ctrl_impl : public e100_codec_ctrl{ +public: +    //structors +    e100_codec_ctrl_impl(spi_iface::sptr iface); +    ~e100_codec_ctrl_impl(void); + +    //aux adc and dac control +    double read_aux_adc(aux_adc_t which); +    void write_aux_dac(aux_dac_t which, double volts); + +    //pga gain control +    void set_tx_pga_gain(double); +    double get_tx_pga_gain(void); +    void set_rx_pga_gain(double, char); +    double get_rx_pga_gain(char); + +private: +    spi_iface::sptr _iface; +    ad9862_regs_t _ad9862_regs; +    void send_reg(boost::uint8_t addr); +    void recv_reg(boost::uint8_t addr); +}; + +/*********************************************************************** + * Codec Control Structors + **********************************************************************/ +e100_codec_ctrl_impl::e100_codec_ctrl_impl(spi_iface::sptr iface){ +    _iface = iface; + +    //soft reset +    _ad9862_regs.soft_reset = 1; +    this->send_reg(0); + +    //initialize the codec register settings +    _ad9862_regs.sdio_bidir = ad9862_regs_t::SDIO_BIDIR_SDIO_SDO; +    _ad9862_regs.lsb_first = ad9862_regs_t::LSB_FIRST_MSB; +    _ad9862_regs.soft_reset = 0; + +    //setup rx side of codec +    _ad9862_regs.byp_buffer_a = 0; +    _ad9862_regs.byp_buffer_b = 0; +    _ad9862_regs.buffer_a_pd = 0; +    _ad9862_regs.buffer_b_pd = 0; +    _ad9862_regs.rx_pga_a = 0;//0x1f;  //TODO bring under api control +    _ad9862_regs.rx_pga_b = 0;//0x1f;  //TODO bring under api control +    _ad9862_regs.rx_twos_comp = 1; +    _ad9862_regs.rx_hilbert = ad9862_regs_t::RX_HILBERT_DIS; +    _ad9862_regs.shared_ref = 1; + +    //setup tx side of codec +    _ad9862_regs.two_data_paths = ad9862_regs_t::TWO_DATA_PATHS_BOTH; +    _ad9862_regs.interleaved = ad9862_regs_t::INTERLEAVED_INTERLEAVED; +    _ad9862_regs.tx_retime = ad9862_regs_t::TX_RETIME_CLKOUT2; +    _ad9862_regs.tx_pga_gain = 199; //TODO bring under api control +    _ad9862_regs.tx_hilbert = ad9862_regs_t::TX_HILBERT_DIS; +    _ad9862_regs.interp = ad9862_regs_t::INTERP_2; +    _ad9862_regs.tx_twos_comp = 1; +    _ad9862_regs.fine_mode = ad9862_regs_t::FINE_MODE_BYPASS; +    _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_BYPASS; +    _ad9862_regs.dac_a_coarse_gain = 0x3; +    _ad9862_regs.dac_b_coarse_gain = 0x3; +    _ad9862_regs.edges = ad9862_regs_t::EDGES_NORMAL; + +    //setup the dll +    _ad9862_regs.input_clk_ctrl = ad9862_regs_t::INPUT_CLK_CTRL_EXTERNAL; +    _ad9862_regs.dll_mult = ad9862_regs_t::DLL_MULT_2; +    _ad9862_regs.dll_mode = ad9862_regs_t::DLL_MODE_FAST; +    _ad9862_regs.hs_duty_cycle = 1; +    _ad9862_regs.clk_duty = 1; + +    //disable clkout1 and clkout2 +    _ad9862_regs.dis1 = ad9862_regs_t::DIS1_DIS; +    //_ad9862_regs.dis2 = ad9862_regs_t::DIS2_DIS; needed for transmit + +    //write the register settings to the codec +    for (uint8_t addr = 0; addr <= 25; addr++){ +        this->send_reg(addr); +    } + +    //always start conversions for aux ADC +    _ad9862_regs.start_a = 1; +    _ad9862_regs.start_b = 1; + +    //aux adc clock +    _ad9862_regs.clk_4 = ad9862_regs_t::CLK_4_1_4; +    this->send_reg(34); +    this->send_reg(35); +} + +e100_codec_ctrl_impl::~e100_codec_ctrl_impl(void){ +    //set aux dacs to zero +    this->write_aux_dac(AUX_DAC_A, 0); +    this->write_aux_dac(AUX_DAC_B, 0); +    this->write_aux_dac(AUX_DAC_C, 0); +    this->write_aux_dac(AUX_DAC_D, 0); + +    //power down +    _ad9862_regs.all_rx_pd = 1; +    this->send_reg(1); +    _ad9862_regs.tx_digital_pd = 1; +    _ad9862_regs.tx_analog_pd = ad9862_regs_t::TX_ANALOG_PD_BOTH; +    this->send_reg(8); +} + +/*********************************************************************** + * Codec Control Gain Control Methods + **********************************************************************/ +static const int mtpgw = 255; //maximum tx pga gain word + +void e100_codec_ctrl_impl::set_tx_pga_gain(double gain){ +    int gain_word = int(mtpgw*(gain - tx_pga_gain_range.start())/(tx_pga_gain_range.stop() - tx_pga_gain_range.start())); +    _ad9862_regs.tx_pga_gain = uhd::clip(gain_word, 0, mtpgw); +    this->send_reg(16); +} + +double e100_codec_ctrl_impl::get_tx_pga_gain(void){ +    return (_ad9862_regs.tx_pga_gain*(tx_pga_gain_range.stop() - tx_pga_gain_range.start())/mtpgw) + tx_pga_gain_range.start(); +} + +static const int mrpgw = 0x14; //maximum rx pga gain word + +void e100_codec_ctrl_impl::set_rx_pga_gain(double gain, char which){ +    int gain_word = int(mrpgw*(gain - rx_pga_gain_range.start())/(rx_pga_gain_range.stop() - rx_pga_gain_range.start())); +    gain_word = uhd::clip(gain_word, 0, mrpgw); +    switch(which){ +    case 'A': +        _ad9862_regs.rx_pga_a = gain_word; +        this->send_reg(2); +        return; +    case 'B': +        _ad9862_regs.rx_pga_b = gain_word; +        this->send_reg(3); +        return; +    default: UHD_THROW_INVALID_CODE_PATH(); +    } +} + +double e100_codec_ctrl_impl::get_rx_pga_gain(char which){ +    int gain_word; +    switch(which){ +    case 'A': gain_word = _ad9862_regs.rx_pga_a; break; +    case 'B': gain_word = _ad9862_regs.rx_pga_b; break; +    default: UHD_THROW_INVALID_CODE_PATH(); +    } +    return (gain_word*(rx_pga_gain_range.stop() - rx_pga_gain_range.start())/mrpgw) + rx_pga_gain_range.start(); +} + +/*********************************************************************** + * Codec Control AUX ADC Methods + **********************************************************************/ +static double aux_adc_to_volts(boost::uint8_t high, boost::uint8_t low){ +    return double((boost::uint16_t(high) << 2) | low)*3.3/0x3ff; +} + +double e100_codec_ctrl_impl::read_aux_adc(aux_adc_t which){ +    switch(which){ +    case AUX_ADC_A1: +        _ad9862_regs.select_a = ad9862_regs_t::SELECT_A_AUX_ADC1; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(28); //read the value (2 bytes, 2 reads) +        this->recv_reg(29); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_a1_9_2, _ad9862_regs.aux_adc_a1_1_0); + +    case AUX_ADC_A2: +        _ad9862_regs.select_a = ad9862_regs_t::SELECT_A_AUX_ADC2; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(26); //read the value (2 bytes, 2 reads) +        this->recv_reg(27); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_a2_9_2, _ad9862_regs.aux_adc_a2_1_0); + +    case AUX_ADC_B1: +        _ad9862_regs.select_b = ad9862_regs_t::SELECT_B_AUX_ADC1; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(32); //read the value (2 bytes, 2 reads) +        this->recv_reg(33); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_b1_9_2, _ad9862_regs.aux_adc_b1_1_0); + +    case AUX_ADC_B2: +        _ad9862_regs.select_b = ad9862_regs_t::SELECT_B_AUX_ADC2; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(30); //read the value (2 bytes, 2 reads) +        this->recv_reg(31); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_b2_9_2, _ad9862_regs.aux_adc_b2_1_0); +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +/*********************************************************************** + * Codec Control AUX DAC Methods + **********************************************************************/ +void e100_codec_ctrl_impl::write_aux_dac(aux_dac_t which, double volts){ +    //special case for aux dac d (aka sigma delta word) +    if (which == AUX_DAC_D){ +        boost::uint16_t dac_word = uhd::clip(boost::math::iround(volts*0xfff/3.3), 0, 0xfff); +        _ad9862_regs.sig_delt_11_4 = boost::uint8_t(dac_word >> 4); +        _ad9862_regs.sig_delt_3_0 = boost::uint8_t(dac_word & 0xf); +        this->send_reg(42); +        this->send_reg(43); +        return; +    } + +    //calculate the dac word for aux dac a, b, c +    boost::uint8_t dac_word = uhd::clip(boost::math::iround(volts*0xff/3.3), 0, 0xff); + +    //setup a lookup table for the aux dac params (reg ref, reg addr) +    typedef boost::tuple<boost::uint8_t*, boost::uint8_t> dac_params_t; +    uhd::dict<aux_dac_t, dac_params_t> aux_dac_to_params = boost::assign::map_list_of +        (AUX_DAC_A, dac_params_t(&_ad9862_regs.aux_dac_a, 36)) +        (AUX_DAC_B, dac_params_t(&_ad9862_regs.aux_dac_b, 37)) +        (AUX_DAC_C, dac_params_t(&_ad9862_regs.aux_dac_c, 38)) +    ; + +    //set the aux dac register +    UHD_ASSERT_THROW(aux_dac_to_params.has_key(which)); +    boost::uint8_t *reg_ref, reg_addr; +    boost::tie(reg_ref, reg_addr) = aux_dac_to_params[which]; +    *reg_ref = dac_word; +    this->send_reg(reg_addr); +} + +/*********************************************************************** + * Codec Control SPI Methods + **********************************************************************/ +void e100_codec_ctrl_impl::send_reg(boost::uint8_t addr){ +    boost::uint32_t reg = _ad9862_regs.get_write_reg(addr); +    UHD_LOGV(often) << "codec control write reg: " << std::hex << reg << std::endl; +    _iface->write_spi( +        UE_SPI_SS_AD9862, +        spi_config_t::EDGE_RISE, +        reg, 16 +    ); +} + +void e100_codec_ctrl_impl::recv_reg(boost::uint8_t addr){ +    boost::uint32_t reg = _ad9862_regs.get_read_reg(addr); +    UHD_LOGV(often) << "codec control read reg: " << std::hex << reg << std::endl; +    boost::uint32_t ret = _iface->read_spi( +        UE_SPI_SS_AD9862, +        spi_config_t::EDGE_RISE, +        reg, 16 +    ); +    UHD_LOGV(often) << "codec control read ret: " << std::hex << ret << std::endl; +    _ad9862_regs.set_reg(addr, boost::uint16_t(ret)); +} + +/*********************************************************************** + * Codec Control Make + **********************************************************************/ +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 new file mode 100644 index 000000000..707f6f521 --- /dev/null +++ b/host/lib/usrp/e100/codec_ctrl.hpp @@ -0,0 +1,90 @@ +// +// 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_USRP_E100_CODEC_CTRL_HPP +#define INCLUDED_USRP_E100_CODEC_CTRL_HPP + +#include <uhd/types/serial.hpp> +#include <uhd/types/ranges.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> + +/*! + * The usrp-e codec control: + * - Init/power down codec. + * - Read aux adc, write aux dac. + */ +class e100_codec_ctrl : boost::noncopyable{ +public: +    typedef boost::shared_ptr<e100_codec_ctrl> sptr; + +    static const uhd::gain_range_t tx_pga_gain_range; +    static const uhd::gain_range_t rx_pga_gain_range; + +    /*! +     * Make a new codec control object. +     * \param iface the spi iface object +     * \return the codec control object +     */ +    static sptr make(uhd::spi_iface::sptr iface); + +    //! aux adc identifier constants +    enum aux_adc_t{ +        AUX_ADC_A2 = 0xA2, +        AUX_ADC_A1 = 0xA1, +        AUX_ADC_B2 = 0xB2, +        AUX_ADC_B1 = 0xB1 +    }; + +    /*! +     * Read an auxiliary adc: +     * The internals remember which aux adc was read last. +     * Therefore, the aux adc switch is only changed as needed. +     * \param which which of the 4 adcs +     * \return a value in volts +     */ +    virtual double read_aux_adc(aux_adc_t which) = 0; + +    //! aux dac identifier constants +    enum aux_dac_t{ +        AUX_DAC_A = 0xA, +        AUX_DAC_B = 0xB, +        AUX_DAC_C = 0xC, +        AUX_DAC_D = 0xD //really the sigma delta output +    }; + +    /*! +     * Write an auxiliary dac. +     * \param which which of the 4 dacs +     * \param volts the level in in volts +     */ +    virtual void write_aux_dac(aux_dac_t which, double volts) = 0; + +    //! Set the TX PGA gain +    virtual void set_tx_pga_gain(double gain) = 0; + +    //! Get the TX PGA gain +    virtual double get_tx_pga_gain(void) = 0; + +    //! Set the RX PGA gain ('A' or 'B') +    virtual void set_rx_pga_gain(double gain, char which) = 0; + +    //! Get the RX PGA gain ('A' or 'B') +    virtual double get_rx_pga_gain(char which) = 0; +}; + +#endif /* INCLUDED_USRP_E100_CODEC_CTRL_HPP */ diff --git a/host/lib/usrp/e100/dboard_iface.cpp b/host/lib/usrp/e100/dboard_iface.cpp new file mode 100644 index 000000000..6afc7bc48 --- /dev/null +++ b/host/lib/usrp/e100/dboard_iface.cpp @@ -0,0 +1,258 @@ +// +// 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 "gpio_core_200.hpp" +#include <uhd/types/serial.hpp> +#include "e100_regs.hpp" +#include "clock_ctrl.hpp" +#include "codec_ctrl.hpp" +#include <uhd/usrp/dboard_iface.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/exception.hpp> +#include <boost/assign/list_of.hpp> +#include <linux/usrp_e.h> //i2c and spi constants + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +class e100_dboard_iface : public dboard_iface{ +public: + +    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 +    ){ +        _wb_iface = wb_iface; +        _i2c_iface = i2c_iface; +        _spi_iface = spi_iface; +        _clock = clock; +        _codec = codec; +        _gpio = gpio_core_200::make(_wb_iface, E100_REG_SR_ADDR(UE_SR_GPIO), E100_REG_RB_GPIO); + +        //init the clock rate shadows +        this->set_clock_rate(UNIT_RX, _clock->get_fpga_clock_rate()); +        this->set_clock_rate(UNIT_TX, _clock->get_fpga_clock_rate()); +    } + +    ~e100_dboard_iface(void){ +        /* NOP */ +    } + +    special_props_t get_special_props(void){ +        special_props_t props; +        props.soft_clock_divider = false; +        props.mangle_i2c_addrs = false; +        return props; +    } + +    void write_aux_dac(unit_t, aux_dac_t, double); +    double read_aux_adc(unit_t, aux_adc_t); + +    void _set_pin_ctrl(unit_t, boost::uint16_t); +    void _set_atr_reg(unit_t, atr_reg_t, boost::uint16_t); +    void _set_gpio_ddr(unit_t, boost::uint16_t); +    void _set_gpio_out(unit_t, boost::uint16_t); +    void set_gpio_debug(unit_t, int); +    boost::uint16_t read_gpio(unit_t); + +    void write_i2c(boost::uint8_t, const byte_vector_t &); +    byte_vector_t read_i2c(boost::uint8_t, size_t); + +    void write_spi( +        unit_t unit, +        const spi_config_t &config, +        boost::uint32_t data, +        size_t num_bits +    ); + +    boost::uint32_t read_write_spi( +        unit_t unit, +        const spi_config_t &config, +        boost::uint32_t data, +        size_t num_bits +    ); + +    void set_clock_rate(unit_t, double); +    std::vector<double> get_clock_rates(unit_t); +    double get_clock_rate(unit_t); +    void set_clock_enabled(unit_t, bool); +    double get_codec_rate(unit_t); + +private: +    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; +    gpio_core_200::sptr _gpio; +}; + +/*********************************************************************** + * Make Function + **********************************************************************/ +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 e100_dboard_iface(wb_iface, i2c_iface, spi_iface, clock, codec)); +} + +/*********************************************************************** + * Clock Rates + **********************************************************************/ +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> 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(); +    default: UHD_THROW_INVALID_CODE_PATH(); +    } +} + +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(); +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +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 e100_dboard_iface::get_codec_rate(unit_t){ +    return _clock->get_fpga_clock_rate(); +} + +/*********************************************************************** + * GPIO + **********************************************************************/ +void e100_dboard_iface::_set_pin_ctrl(unit_t unit, boost::uint16_t value){ +    return _gpio->set_pin_ctrl(unit, value); +} + +void e100_dboard_iface::_set_gpio_ddr(unit_t unit, boost::uint16_t value){ +    return _gpio->set_gpio_ddr(unit, value); +} + +void e100_dboard_iface::_set_gpio_out(unit_t unit, boost::uint16_t value){ +    return _gpio->set_gpio_out(unit, value); +} + +boost::uint16_t e100_dboard_iface::read_gpio(unit_t unit){ +    return _gpio->read_gpio(unit); +} + +void e100_dboard_iface::_set_atr_reg(unit_t unit, atr_reg_t atr, boost::uint16_t value){ +    return _gpio->set_atr_reg(unit, atr, value); +} + +void e100_dboard_iface::set_gpio_debug(unit_t, int){ +    throw uhd::not_implemented_error("no set_gpio_debug implemented"); +} + +/*********************************************************************** + * SPI + **********************************************************************/ +/*! + * Static function to convert a unit type to a spi slave device number. + * \param unit the dboard interface unit type enum + * \return the slave device number + */ +static boost::uint32_t unit_to_otw_spi_dev(dboard_iface::unit_t unit){ +    switch(unit){ +    case dboard_iface::UNIT_TX: return UE_SPI_SS_TX_DB; +    case dboard_iface::UNIT_RX: return UE_SPI_SS_RX_DB; +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +void e100_dboard_iface::write_spi( +    unit_t unit, +    const spi_config_t &config, +    boost::uint32_t data, +    size_t num_bits +){ +    _spi_iface->write_spi(unit_to_otw_spi_dev(unit), config, data, num_bits); +} + +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 _spi_iface->read_spi(unit_to_otw_spi_dev(unit), config, data, num_bits); +} + +/*********************************************************************** + * I2C + **********************************************************************/ +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 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 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) +        (AUX_DAC_B, e100_codec_ctrl::AUX_DAC_B) +        (AUX_DAC_C, e100_codec_ctrl::AUX_DAC_C) +        (AUX_DAC_D, e100_codec_ctrl::AUX_DAC_D) +    ; +    _codec->write_aux_dac(which_to_aux_dac[which], value); +} + +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 +        (UNIT_RX, map_list_of +            (AUX_ADC_A, e100_codec_ctrl::AUX_ADC_A1) +            (AUX_ADC_B, e100_codec_ctrl::AUX_ADC_B1) +        ) +        (UNIT_TX, map_list_of +            (AUX_ADC_A, e100_codec_ctrl::AUX_ADC_A2) +            (AUX_ADC_B, e100_codec_ctrl::AUX_ADC_B2) +        ) +    ; +    return _codec->read_aux_adc(unit_to_which_to_aux_adc[unit][which]); +} diff --git a/host/lib/usrp/e100/e100_ctrl.cpp b/host/lib/usrp/e100/e100_ctrl.cpp new file mode 100644 index 000000000..eb529c9c1 --- /dev/null +++ b/host/lib/usrp/e100/e100_ctrl.cpp @@ -0,0 +1,355 @@ +// +// 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 "e100_ctrl.hpp" +#include "e100_regs.hpp" +#include <uhd/exception.hpp> +#include <uhd/utils/log.hpp> +#include <uhd/utils/msg.hpp> +#include <sys/ioctl.h> //ioctl +#include <fcntl.h> //open, close +#include <linux/usrp_e.h> //ioctl structures and constants +#include <boost/thread/thread.hpp> //sleep +#include <boost/thread/mutex.hpp> +#include <boost/foreach.hpp> +#include <boost/format.hpp> +#include <fstream> + +using namespace uhd; + +/*********************************************************************** + * Sysfs GPIO wrapper class + **********************************************************************/ +class gpio{ +public: +    gpio(const int num, const std::string &dir) : _num(num){ +        this->set_xport("export"); +        this->set_dir(dir); +        _value_file.open(str(boost::format("/sys/class/gpio/gpio%d/value") % num).c_str(), std::ios_base::in | std::ios_base::out); +    } +    ~gpio(void){ +        _value_file.close(); +        this->set_dir("in"); +        this->set_xport("unexport"); +    } +    void operator()(const int val){ +        _value_file << val << std::endl << std::flush; +    } +    int operator()(void){ +        std::string val; +        std::getline(_value_file, val); +        _value_file.seekg(0); +        return int(val.at(0) - '0') & 0x1; +    } +private: +    void set_xport(const std::string &xport){ +        std::ofstream export_file(("/sys/class/gpio/" + xport).c_str()); +        export_file << _num << std::endl << std::flush; +        export_file.close(); +    } +    void set_dir(const std::string &dir){ +        std::ofstream dir_file(str(boost::format("/sys/class/gpio/gpio%d/direction") % _num).c_str()); +        dir_file << dir << std::endl << std::flush; +        dir_file.close(); +    } +    const int _num; +    std::fstream _value_file; +}; + +/*********************************************************************** + * 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){ +        if ((_node_fd = ::open(node.c_str(), O_RDWR)) < 0){ +            throw uhd::io_error("Failed to open " + node); +        } +    } + +    ~i2c_dev_iface(void){ +        ::close(_node_fd); +    } + +    void write_i2c(boost::uint8_t addr, const byte_vector_t &bytes){ +        byte_vector_t rw_bytes(bytes); + +        //setup the message +        i2c_msg msg; +        msg.addr = addr; +        msg.flags = 0; +        msg.len = bytes.size(); +        msg.buf = &rw_bytes.front(); + +        //setup the data +        i2c_rdwr_ioctl_data data; +        data.msgs = &msg; +        data.nmsgs = 1; + +        //call the ioctl +        UHD_ASSERT_THROW(::ioctl(_node_fd, I2C_RDWR, &data) >= 0); +    } + +    byte_vector_t read_i2c(boost::uint8_t addr, size_t num_bytes){ +        byte_vector_t bytes(num_bytes); + +        //setup the message +        i2c_msg msg; +        msg.addr = addr; +        msg.flags = I2C_M_RD; +        msg.len = bytes.size(); +        msg.buf = &bytes.front(); + +        //setup the data +        i2c_rdwr_ioctl_data data; +        data.msgs = &msg; +        data.nmsgs = 1; + +        //call the ioctl +        UHD_ASSERT_THROW(::ioctl(_node_fd, I2C_RDWR, &data) >= 0); + +        return bytes; +    } + +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)); +} + +/*********************************************************************** + * UART control implementation + **********************************************************************/ +#include <termios.h> +#include <cstring> +class uart_dev_iface : public uart_iface{ +public: +    uart_dev_iface(const std::string &node){ +        if ((_node_fd = ::open(node.c_str(), O_RDWR | O_NONBLOCK)) < 0){ +            throw uhd::io_error("Failed to open " + node); +        } + +        //init the tty settings w/ termios +        termios tio; +        std::memset(&tio,0,sizeof(tio)); +        tio.c_iflag = IGNCR; //Ignore CR +        tio.c_oflag = OPOST | ONLCR; //Map NL to CR-NL on output +        tio.c_cflag = CS8 | CREAD | CLOCAL; // 8n1 +        tio.c_lflag = 0; + +        cfsetospeed(&tio, B115200);            // 115200 baud +        cfsetispeed(&tio, B115200);            // 115200 baud + +        tcsetattr(_node_fd, TCSANOW, &tio); +    } + +    void write_uart(const std::string &buf){ +        const ssize_t ret = ::write(_node_fd, buf.c_str(), buf.size()); +        if (size_t(ret) != buf.size()) UHD_LOG << ret; +    } + +    std::string read_uart(double timeout){ +        const boost::system_time exit_time = boost::get_system_time() + boost::posix_time::milliseconds(long(timeout*1000)); + +        std::string line; +        while(true){ +            char ch; +            const ssize_t ret = ::read(_node_fd, &ch, 1); + +            //got a character -> process it +            if (ret == 1){ +                const bool flush  = ch == '\n' or ch == '\r'; +                if (flush and line.empty()) continue; //avoid flushing on empty lines +                line += std::string(1, ch); +                if (flush) break; +            } + +            //didnt get a character, check the timeout +            else if (boost::get_system_time() > exit_time){ +                break; +            } + +            //otherwise sleep for a bit +            else{ +                boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +            } +        } +        return line; +    } + +private: int _node_fd; +}; + +uhd::uart_iface::sptr e100_ctrl::make_gps_uart_iface(const std::string &node){ +    return uhd::uart_iface::sptr(new uart_dev_iface(node)); +} + +/*********************************************************************** + * USRP-E100 control implementation + **********************************************************************/ +class e100_ctrl_impl : public e100_ctrl{ +public: + +    int get_file_descriptor(void){ +        return _node_fd; +    } + +    /******************************************************************* +     * 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 +        if ((_node_fd = ::open(node.c_str(), O_RDWR)) < 0){ +            throw uhd::io_error("Failed to open " + node); +        } + +        //check the module compatibility number +        int module_compat_num = ::ioctl(_node_fd, USRP_E_GET_COMPAT_NUMBER, NULL); +        if (module_compat_num != USRP_E_COMPAT_NUMBER){ +            throw uhd::runtime_error(str(boost::format( +                "Expected module compatibility number 0x%x, but got 0x%x:\n" +                "The module build is not compatible with the host code build." +            ) % USRP_E_COMPAT_NUMBER % module_compat_num)); +        } + +        //perform a global reset after opening +        this->poke32(E100_REG_GLOBAL_RESET, 0); +    } + +    ~e100_ctrl_impl(void){ +        ::close(_node_fd); +    } + +    /******************************************************************* +     * IOCTL: provides the communication base for all other calls +     ******************************************************************/ +    void ioctl(int request, void *mem){ +        boost::mutex::scoped_lock lock(_ioctl_mutex); + +        if (::ioctl(_node_fd, request, mem) < 0){ +            throw uhd::os_error(str( +                boost::format("ioctl failed with request %d") % request +            )); +        } +    } +    /******************************************************************* +     * Peek and Poke +     ******************************************************************/ +    void poke32(wb_addr_type addr, boost::uint32_t value){ +        //load the data struct +        usrp_e_ctl32 data; +        data.offset = addr; +        data.count = 1; +        data.buf[0] = value; + +        //call the ioctl +        this->ioctl(USRP_E_WRITE_CTL32, &data); +    } + +    void poke16(wb_addr_type addr, boost::uint16_t value){ +        //load the data struct +        usrp_e_ctl16 data; +        data.offset = addr; +        data.count = 1; +        data.buf[0] = value; + +        //call the ioctl +        this->ioctl(USRP_E_WRITE_CTL16, &data); +    } + +    boost::uint32_t peek32(wb_addr_type addr){ +        //load the data struct +        usrp_e_ctl32 data; +        data.offset = addr; +        data.count = 1; + +        //call the ioctl +        this->ioctl(USRP_E_READ_CTL32, &data); + +        return data.buf[0]; +    } + +    boost::uint16_t peek16(wb_addr_type addr){ +        //load the data struct +        usrp_e_ctl16 data; +        data.offset = addr; +        data.count = 1; + +        //call the ioctl +        this->ioctl(USRP_E_READ_CTL16, &data); + +        return data.buf[0]; +    } + +private: +    int _node_fd; +    boost::mutex _ioctl_mutex; +}; + +/*********************************************************************** + * Public Make Function + **********************************************************************/ +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..fd66791d4 --- /dev/null +++ b/host/lib/usrp/e100/e100_ctrl.hpp @@ -0,0 +1,48 @@ +// +// 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); + +    //! Make a uart iface for the uart device node +    static uhd::uart_iface::sptr make_gps_uart_iface(const std::string &node); + +    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_impl.cpp b/host/lib/usrp/e100/e100_impl.cpp new file mode 100644 index 000000000..d55ea5ec5 --- /dev/null +++ b/host/lib/usrp/e100/e100_impl.cpp @@ -0,0 +1,498 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "apply_corrections.hpp" +#include "e100_impl.hpp" +#include "e100_regs.hpp" +#include <uhd/utils/msg.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/images.hpp> +#include <boost/bind.hpp> +#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 + **********************************************************************/ +static device_addrs_t e100_find(const device_addr_t &hint){ +    device_addrs_t e100_addrs; + +    //return an empty list of addresses when type is set to non-usrp-e +    if (hint.has_key("type") and hint["type"] != "e100") return e100_addrs; + +    //device node not provided, assume its 0 +    if (not hint.has_key("node")){ +        device_addr_t new_addr = hint; +        new_addr["node"] = "/dev/usrp_e0"; +        return e100_find(new_addr); +    } + +    //use the given device node name +    if (fs::exists(hint["node"])){ +        device_addr_t new_addr; +        new_addr["type"] = "e100"; +        new_addr["node"] = fs::system_complete(fs::path(hint["node"])).string(); +        try{ +            i2c_iface::sptr i2c_iface = e100_ctrl::make_dev_i2c_iface(E100_I2C_DEV_NODE); +            const mboard_eeprom_t mb_eeprom(*i2c_iface, E100_EEPROM_MAP_KEY); +            new_addr["name"] = mb_eeprom["name"]; +            new_addr["serial"] = mb_eeprom["serial"]; +        } +        catch(const std::exception &e){ +            new_addr["name"] = ""; +            new_addr["serial"] = ""; +        } +        if ( +            (not hint.has_key("name")   or hint["name"]   == new_addr["name"]) and +            (not hint.has_key("serial") or hint["serial"] == new_addr["serial"]) +        ){ +            e100_addrs.push_back(new_addr); +        } +    } + +    return e100_addrs; +} + +/*********************************************************************** + * Make + **********************************************************************/ +static size_t hash_fpga_file(const std::string &file_path){ +    size_t hash = 0; +    std::ifstream file(file_path.c_str()); +    if (not file.good()) throw uhd::io_error("cannot open fpga file for read: " + file_path); +    while (file.good()) boost::hash_combine(hash, file.get()); +    file.close(); +    return hash; +} + +static device::sptr e100_make(const device_addr_t &device_addr){ +    return device::sptr(new e100_impl(device_addr)); +} + +UHD_STATIC_BLOCK(register_e100_device){ +    device::register_device(&e100_find, &e100_make); +} + +static const uhd::dict<std::string, std::string> model_to_fpga_file_name = boost::assign::map_list_of +    ("E100", "usrp_e100_fpga_v2.bin") +    ("E110", "usrp_e110_fpga.bin") +; + +/*********************************************************************** + * Structors + **********************************************************************/ +e100_impl::e100_impl(const uhd::device_addr_t &device_addr){ +    _tree = property_tree::make(); + +    //setup the main interface into fpga +    const std::string node = device_addr["node"]; +    _fpga_ctrl = e100_ctrl::make(node); + +    //read the eeprom so we can determine the hardware +    _dev_i2c_iface = e100_ctrl::make_dev_i2c_iface(E100_I2C_DEV_NODE); +    const mboard_eeprom_t mb_eeprom(*_dev_i2c_iface, E100_EEPROM_MAP_KEY); + +    //determine the model string for this device +    const std::string model = device_addr.get("model", mb_eeprom.get("model", "")); +    if (not model_to_fpga_file_name.has_key(model)) throw uhd::runtime_error(str(boost::format( +        "\n" +        "  The specified model string \"%s\" is not recognized.\n" +        "  Perhaps the EEPROM is uninitialized, missing, or damaged.\n" +        "  Or, a monitor is pirating the I2C address of the EEPROM.\n" +    ) % model)); + +    //extract the fpga path and compute hash +    const std::string default_fpga_file_name = model_to_fpga_file_name[model]; +    const std::string e100_fpga_image = find_image_path(device_addr.get("fpga", default_fpga_file_name)); +    const boost::uint32_t file_hash = boost::uint32_t(hash_fpga_file(e100_fpga_image)); + +    //When the hash does not match: +    // - close the device node +    // - load the fpga bin file +    // - re-open the device node +    if (_fpga_ctrl->peek32(E100_REG_RB_MISC_TEST32) != file_hash){ +        _fpga_ctrl.reset(); +        e100_load_fpga(e100_fpga_image); +        _fpga_ctrl = e100_ctrl::make(node); +    } + +    //setup clock control here to ensure that the FPGA has a good clock before we continue +    bool dboard_clocks_diff = true; +    if      (mb_eeprom.get("revision", "0") == "3") dboard_clocks_diff = false; +    else if (mb_eeprom.get("revision", "0") == "4") dboard_clocks_diff = true; +    else UHD_MSG(warning) +        << "Unknown E1XX revision number!\n" +        << "defaulting to differential dboard clocks to be safe.\n" +        << std::endl; +    const double master_clock_rate = device_addr.cast<double>("master_clock_rate", E100_DEFAULT_CLOCK_RATE); +    _aux_spi_iface = e100_ctrl::make_aux_spi_iface(); +    _clock_ctrl = e100_clock_ctrl::make(_aux_spi_iface, master_clock_rate, dboard_clocks_diff); + +    //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++){ +        _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; + +    if (test_fail) UHD_MSG(error) << boost::format( +        "The FPGA is either clocked improperly\n" +        "or the FPGA build is not compatible.\n" +        "Subsequent errors may follow...\n" +    ); + +    //check that the compatibility is correct +    this->check_fpga_compat(); + +    //////////////////////////////////////////////////////////////////// +    // 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)); +    _data_transport = e100_make_mmap_zero_copy(_fpga_ctrl); + +    //////////////////////////////////////////////////////////////////// +    // Initialize the properties tree +    //////////////////////////////////////////////////////////////////// +    _tree->create<std::string>("/name").set("E-Series Device"); +    const fs_path mb_path = "/mboards/0"; +    _tree->create<std::string>(mb_path / "name").set(model); +    _tree->create<std::string>(mb_path / "codename").set("Euwanee"); + +    //////////////////////////////////////////////////////////////////// +    // setup the mboard eeprom +    //////////////////////////////////////////////////////////////////// +    _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 fs_path rx_codec_path = mb_path / "rx_codecs/A"; +    const fs_path tx_codec_path = mb_path / "tx_codecs/A"; +    _tree->create<std::string>(rx_codec_path / "name").set("ad9522"); +    _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 +    //////////////////////////////////////////////////////////////////// +    _tree->create<sensor_value_t>(mb_path / "sensors/ref_locked") +        .publish(boost::bind(&e100_impl::get_ref_locked, this)); + +    //////////////////////////////////////////////////////////////////// +    // Create the GPSDO control +    //////////////////////////////////////////////////////////////////// +    try{ +        _gps = gps_ctrl::make(e100_ctrl::make_gps_uart_iface(E100_UART_DEV_NODE)); +    } +    catch(std::exception &e){ +        UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl; +    } +    if (_gps.get() != NULL and _gps->gps_detected()){ +        BOOST_FOREACH(const std::string &name, _gps->get_sensors()){ +            _tree->create<sensor_value_t>(mb_path / "sensors" / name) +                .publish(boost::bind(&gps_ctrl::get_sensor, _gps, name)); +        } +    } + +    //////////////////////////////////////////////////////////////////// +    // 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)); + +    _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)); + +    const fs_path rx_fe_path = mb_path / "rx_frontends" / "A"; +    const fs_path tx_fe_path = mb_path / "tx_frontends" / "A"; + +    _tree->create<std::complex<double> >(rx_fe_path / "dc_offset" / "value") +        .coerce(boost::bind(&rx_frontend_core_200::set_dc_offset, _rx_fe, _1)) +        .set(std::complex<double>(0.0, 0.0)); +    _tree->create<bool>(rx_fe_path / "dc_offset" / "enable") +        .subscribe(boost::bind(&rx_frontend_core_200::set_dc_offset_auto, _rx_fe, _1)) +        .set(true); +    _tree->create<std::complex<double> >(rx_fe_path / "iq_balance" / "value") +        .subscribe(boost::bind(&rx_frontend_core_200::set_iq_balance, _rx_fe, _1)) +        .set(std::complex<double>(0.0, 0.0)); +    _tree->create<std::complex<double> >(tx_fe_path / "dc_offset" / "value") +        .coerce(boost::bind(&tx_frontend_core_200::set_dc_offset, _tx_fe, _1)) +        .set(std::complex<double>(0.0, 0.0)); +    _tree->create<std::complex<double> >(tx_fe_path / "iq_balance" / "value") +        .subscribe(boost::bind(&tx_frontend_core_200::set_iq_balance, _tx_fe, _1)) +        .set(std::complex<double>(0.0, 0.0)); + +    //////////////////////////////////////////////////////////////////// +    // 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_RX_LINK_RATE_BPS); +        _tree->access<double>(mb_path / "tick_rate") +            .subscribe(boost::bind(&rx_dsp_core_200::set_tick_rate, _rx_dsps[dspno], _1)); +        fs_path rx_dsp_path = mb_path / str(boost::format("rx_dsps/%u") % dspno); +        _tree->create<meta_range_t>(rx_dsp_path / "rate/range") +            .publish(boost::bind(&rx_dsp_core_200::get_host_rates, _rx_dsps[dspno])); +        _tree->create<double>(rx_dsp_path / "rate/value") +            .set(1e6) //some default +            .coerce(boost::bind(&rx_dsp_core_200::set_host_rate, _rx_dsps[dspno], _1)) +            .subscribe(boost::bind(&e100_impl::update_rx_samp_rate, this, dspno, _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 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_TX_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<meta_range_t>(mb_path / "tx_dsps/0/rate/range") +        .publish(boost::bind(&tx_dsp_core_200::get_host_rates, _tx_dsp)); +    _tree->create<double>(mb_path / "tx_dsps/0/rate/value") +        .set(1e6) //some default +        .coerce(boost::bind(&tx_dsp_core_200::set_host_rate, _tx_dsp, _1)) +        .subscribe(boost::bind(&e100_impl::update_tx_samp_rate, this, 0, _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_hi_now = E100_REG_RB_TIME_NOW_HI; +    time64_rb_bases.rb_lo_now = E100_REG_RB_TIME_NOW_LO; +    time64_rb_bases.rb_hi_pps = E100_REG_RB_TIME_PPS_HI; +    time64_rb_bases.rb_lo_pps = E100_REG_RB_TIME_PPS_LO; +    _time64 = 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)); +    std::vector<std::string> clock_sources = boost::assign::list_of("internal")("external")("auto"); +    if (_gps and _gps->gps_detected()) clock_sources.push_back("gpsdo"); +    _tree->create<std::vector<std::string> >(mb_path / "clock_source/options").set(clock_sources); + +    //////////////////////////////////////////////////////////////////// +    // create user-defined control objects +    //////////////////////////////////////////////////////////////////// +    _user = user_settings_core_200::make(_fpga_ctrl, E100_REG_SR_ADDR(UE_SR_USER_REGS)); +    _tree->create<user_settings_core_200::user_reg_t>(mb_path / "user/regs") +        .subscribe(boost::bind(&user_settings_core_200::set_reg, _user, _1)); + +    //////////////////////////////////////////////////////////////////// +    // 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, tx_db_eeprom.id, gdb_eeprom.id, +        _dboard_iface, _tree->subtree(mb_path / "dboards/A") +    ); + +    //bind frontend corrections to the dboard freq props +    const fs_path db_tx_fe_path = mb_path / "dboards" / "A" / "tx_frontends"; +    BOOST_FOREACH(const std::string &name, _tree->list(db_tx_fe_path)){ +        _tree->access<double>(db_tx_fe_path / name / "freq" / "value") +            .subscribe(boost::bind(&e100_impl::set_tx_fe_corrections, this, _1)); +    } +    const fs_path db_rx_fe_path = mb_path / "dboards" / "A" / "rx_frontends"; +    BOOST_FOREACH(const std::string &name, _tree->list(db_rx_fe_path)){ +        _tree->access<double>(db_rx_fe_path / name / "freq" / "value") +            .subscribe(boost::bind(&e100_impl::set_rx_fe_corrections, this, _1)); +    } + +    //initialize io handling +    this->io_init(); + +    //////////////////////////////////////////////////////////////////// +    // do some post-init tasks +    //////////////////////////////////////////////////////////////////// +    this->update_rates(); + +    _tree->access<double>(mb_path / "tick_rate") //now subscribe the clock rate setter +        .subscribe(boost::bind(&e100_clock_ctrl::set_fpga_clock_rate, _clock_ctrl, _1)); + +    //reset cordic rates and their properties to zero +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){ +        _tree->access<double>(mb_path / "rx_dsps" / name / "freq" / "value").set(0.0); +    } +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +        _tree->access<double>(mb_path / "tx_dsps" / name / "freq" / "value").set(0.0); +    } + +    _tree->access<subdev_spec_t>(mb_path / "rx_subdev_spec").set(subdev_spec_t("A:" + _tree->list(mb_path / "dboards/A/rx_frontends").at(0))); +    _tree->access<subdev_spec_t>(mb_path / "tx_subdev_spec").set(subdev_spec_t("A:" + _tree->list(mb_path / "dboards/A/tx_frontends").at(0))); +    _tree->access<std::string>(mb_path / "clock_source/value").set("internal"); +    _tree->access<std::string>(mb_path / "time_source/value").set("none"); + +    //GPS installed: use external ref, time, and init time spec +    if (_gps and _gps->gps_detected()){ +        _time64->enable_gpsdo(); +        UHD_MSG(status) << "Setting references to the internal GPSDO" << std::endl; +        _tree->access<std::string>(mb_path / "time_source/value").set("gpsdo"); +        _tree->access<std::string>(mb_path / "clock_source/value").set("gpsdo"); +        UHD_MSG(status) << "Initializing time to the internal GPSDO" << std::endl; +        _time64->set_time_next_pps(time_spec_t(time_t(_gps->get_sensor("gps_time").to_int()+1))); +    } + +} + +e100_impl::~e100_impl(void){ +    /* NOP */ +} + +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'); +} + +void e100_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){ +    mb_eeprom.commit(*_dev_i2c_iface, E100_EEPROM_MAP_KEY); +} + +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); +} + +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 if (source == "gpsdo")    _clock_ctrl->use_external_ref(); +    else throw uhd::runtime_error("unhandled clock configuration reference source: " + source); +} + +sensor_value_t e100_impl::get_ref_locked(void){ +    const bool lock = _clock_ctrl->get_locked(); +    return sensor_value_t("Ref", lock, "locked", "unlocked"); +} + +void e100_impl::check_fpga_compat(void){ +    const boost::uint32_t fpga_compat_num = _fpga_ctrl->peek32(E100_REG_RB_COMPAT); +    boost::uint16_t fpga_major = fpga_compat_num >> 16, fpga_minor = fpga_compat_num & 0xffff; +    if (fpga_major == 0){ //old version scheme +        fpga_major = fpga_minor; +        fpga_minor = 0; +    } +    if (fpga_major != E100_FPGA_COMPAT_NUM){ +        throw uhd::runtime_error(str(boost::format( +            "Expected FPGA compatibility number %d, but got %d:\n" +            "The FPGA build is not compatible with the host code build." +        ) % int(E100_FPGA_COMPAT_NUM) % fpga_major)); +    } +    _tree->create<std::string>("/mboards/0/fpga_version").set(str(boost::format("%u.%u") % fpga_major % fpga_minor)); +} + +void e100_impl::set_rx_fe_corrections(const double lo_freq){ +    apply_rx_fe_corrections(this->get_tree()->subtree("/mboards/0"), "A", lo_freq); +} + +void e100_impl::set_tx_fe_corrections(const double lo_freq){ +    apply_tx_fe_corrections(this->get_tree()->subtree("/mboards/0"), "A", lo_freq); +} diff --git a/host/lib/usrp/e100/e100_impl.hpp b/host/lib/usrp/e100/e100_impl.hpp new file mode 100644 index 000000000..381c085e0 --- /dev/null +++ b/host/lib/usrp/e100/e100_impl.hpp @@ -0,0 +1,141 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "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 "user_settings_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/usrp/gps_ctrl.hpp> +#include <uhd/types/sensors.hpp> +#include <uhd/types/stream_cmd.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <uhd/transport/zero_copy.hpp> +#include <boost/weak_ptr.hpp> + +#ifndef INCLUDED_E100_IMPL_HPP +#define INCLUDED_E100_IMPL_HPP + +uhd::transport::zero_copy_if::sptr e100_make_mmap_zero_copy(e100_ctrl::sptr iface); + +// = gpmc_clock_rate/clk_div/cycles_per_transaction*bytes_per_transaction +static const double          E100_RX_LINK_RATE_BPS = 166e6/3/2*2; +static const double          E100_TX_LINK_RATE_BPS = 166e6/3/1*2; +static const std::string     E100_I2C_DEV_NODE = "/dev/i2c-3"; +static const std::string     E100_UART_DEV_NODE = "/dev/ttyO0"; +static const boost::uint16_t E100_FPGA_COMPAT_NUM = 10; +static const boost::uint32_t E100_RX_SID_BASE = 2; +static const boost::uint32_t E100_TX_ASYNC_SID = 1; +static const double          E100_DEFAULT_CLOCK_RATE = 64e6; +static const std::string     E100_EEPROM_MAP_KEY = "E100"; + +//! load an fpga image from a bin file into the usrp-e fpga +extern void e100_load_fpga(const std::string &bin_file); + +//! 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 +); + +/*! + * USRP-E100 implementation guts: + * The implementation details are encapsulated here. + * Handles properties on the mboard, dboard, dsps... + */ +class e100_impl : public uhd::device{ +public: +    //structors +    e100_impl(const uhd::device_addr_t &); +    ~e100_impl(void); + +    //the io interface +    uhd::rx_streamer::sptr get_rx_stream(const uhd::stream_args_t &args); +    uhd::tx_streamer::sptr get_tx_stream(const uhd::stream_args_t &args); +    bool recv_async_msg(uhd::async_metadata_t &, double); + +private: +    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; +    user_settings_core_200::sptr _user; +    e100_clock_ctrl::sptr _clock_ctrl; +    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; +    uhd::gps_ctrl::sptr _gps; + +    //transports +    uhd::transport::zero_copy_if::sptr _data_transport; + +    //dboard stuff +    uhd::usrp::dboard_manager::sptr _dboard_manager; +    uhd::usrp::dboard_iface::sptr _dboard_iface; + +    //handle io stuff +    UHD_PIMPL_DECL(io_impl) _io_impl; +    void io_init(void); + +    //device properties interface +    uhd::property_tree::sptr get_tree(void) const{ +        return _tree; +    } + +    std::vector<boost::weak_ptr<uhd::rx_streamer> > _rx_streamers; +    std::vector<boost::weak_ptr<uhd::tx_streamer> > _tx_streamers; + +    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 size_t, const double rate); +    void update_tx_samp_rate(const size_t, const double rate); +    void update_rates(void); +    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 &); +    uhd::sensor_value_t get_ref_locked(void); +    void check_fpga_compat(void); +    void set_rx_fe_corrections(const double); +    void set_tx_fe_corrections(const double); + +}; + +#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 new file mode 100644 index 000000000..58beeb424 --- /dev/null +++ b/host/lib/usrp/e100/e100_mmap_zero_copy.cpp @@ -0,0 +1,262 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "e100_ctrl.hpp" +#include <uhd/transport/zero_copy.hpp> +#include <uhd/utils/log.hpp> +#include <uhd/exception.hpp> +#include <boost/make_shared.hpp> +#include <linux/usrp_e.h> +#include <sys/mman.h> //mmap +#include <unistd.h> //getpagesize +#include <poll.h> //poll +#include <vector> + +using namespace uhd; +using namespace uhd::transport; + +#define fp_verbose false //fast-path verbose +static const size_t poll_breakout = 10; //how many poll timeouts constitute a full timeout + +/*********************************************************************** + * Reusable managed receiver buffer: + *  - The buffer knows how to claim and release a frame. + **********************************************************************/ +class e100_mmap_zero_copy_mrb : public managed_recv_buffer{ +public: +    e100_mmap_zero_copy_mrb(void *mem, ring_buffer_info *info): +        _mem(mem), _info(info) { /* NOP */ } + +    void release(void){ +        if (fp_verbose) UHD_LOGV(always) << "recv buff: release" << std::endl; +        _info->flags = RB_KERNEL; //release the frame +    } + +    UHD_INLINE bool ready(void){return _info->flags & RB_USER;} + +    UHD_INLINE sptr get_new(void){ +        if (fp_verbose) UHD_LOGV(always) << "  make_recv_buff: " << _info->len << std::endl; +        _info->flags = RB_USER_PROCESS; //claim the frame +        return make(this, _mem, _info->len); +    } + +private: +    void *_mem; +    ring_buffer_info *_info; +}; + +/*********************************************************************** + * Reusable managed send buffer: + *  - The buffer knows how to claim and release a frame. + **********************************************************************/ +class e100_mmap_zero_copy_msb : public managed_send_buffer{ +public: +    e100_mmap_zero_copy_msb(void *mem, ring_buffer_info *info, size_t len, int fd): +        _mem(mem), _info(info), _len(len), _fd(fd) { /* NOP */ } + +    void release(void){ +        if (fp_verbose) UHD_LOGV(always) << "send buff: commit " << size() << std::endl; +        _info->len = size(); +        _info->flags = RB_USER; //release the frame +        if (::write(_fd, NULL, 0) < 0){ //notifies the kernel +            UHD_LOGV(rarely) << UHD_THROW_SITE_INFO("write error") << std::endl; +        } +    } + +    UHD_INLINE bool ready(void){return _info->flags & RB_KERNEL;} + +    UHD_INLINE sptr get_new(void){ +        if (fp_verbose) UHD_LOGV(always) << "  make_send_buff: " << _len << std::endl; +        _info->flags = RB_USER_PROCESS; //claim the frame +        return make(this, _mem, _len); +    } + +private: +    void *_mem; +    ring_buffer_info *_info; +    size_t _len; +    int _fd; +}; + +/*********************************************************************** + * The zero copy interface implementation + **********************************************************************/ +class e100_mmap_zero_copy_impl : public zero_copy_if{ +public: +    e100_mmap_zero_copy_impl(e100_ctrl::sptr iface): +        _fd(iface->get_file_descriptor()), _recv_index(0), _send_index(0) +    { +        //get system sizes +        iface->ioctl(USRP_E_GET_RB_INFO, &_rb_size); +        size_t page_size = getpagesize(); +        _frame_size = page_size/2; + +        //calculate the memory size +        _map_size = +            (_rb_size.num_pages_rx_flags + _rb_size.num_pages_tx_flags) * page_size + +            (_rb_size.num_rx_frames + _rb_size.num_tx_frames) * _frame_size; + +        //print sizes summary +        UHD_LOG +            << "page_size:          " << page_size                   << std::endl +            << "frame_size:         " << _frame_size                 << std::endl +            << "num_pages_rx_flags: " << _rb_size.num_pages_rx_flags << std::endl +            << "num_rx_frames:      " << _rb_size.num_rx_frames      << std::endl +            << "num_pages_tx_flags: " << _rb_size.num_pages_tx_flags << std::endl +            << "num_tx_frames:      " << _rb_size.num_tx_frames      << std::endl +            << "map_size:           " << _map_size                   << std::endl +        ; + +        //call mmap to get the memory +        _mapped_mem = ::mmap( +            NULL, _map_size, PROT_READ | PROT_WRITE, MAP_SHARED, _fd, 0 +        ); +        UHD_ASSERT_THROW(_mapped_mem != MAP_FAILED); + +        //calculate the memory offsets for info and buffers +        size_t recv_info_off = 0; +        size_t recv_buff_off = recv_info_off + (_rb_size.num_pages_rx_flags * page_size); +        size_t send_info_off = recv_buff_off + (_rb_size.num_rx_frames * _frame_size); +        size_t send_buff_off = send_info_off + (_rb_size.num_pages_tx_flags * page_size); + +        //print offset summary +        UHD_LOG +            << "recv_info_off: " << recv_info_off << std::endl +            << "recv_buff_off: " << recv_buff_off << std::endl +            << "send_info_off: " << send_info_off << std::endl +            << "send_buff_off: " << send_buff_off << std::endl +        ; + +        //pointers to sections in the mapped memory +        ring_buffer_info (*recv_info)[], (*send_info)[]; +        char *recv_buff, *send_buff; + +        //set the internal pointers for info and buffers +        typedef ring_buffer_info (*rbi_pta)[]; +        char *rb_ptr = reinterpret_cast<char *>(_mapped_mem); +        recv_info = reinterpret_cast<rbi_pta>(rb_ptr + recv_info_off); +        recv_buff = rb_ptr + recv_buff_off; +        send_info = reinterpret_cast<rbi_pta>(rb_ptr + send_info_off); +        send_buff = rb_ptr + send_buff_off; + +        //initialize the managed receive buffers +        for (size_t i = 0; i < get_num_recv_frames(); i++){ +            _mrb_pool.push_back(boost::make_shared<e100_mmap_zero_copy_mrb>( +                recv_buff + get_recv_frame_size()*i, (*recv_info) + i +            )); +        } + +        //initialize the managed send buffers +        for (size_t i = 0; i < get_num_recv_frames(); i++){ +            _msb_pool.push_back(boost::make_shared<e100_mmap_zero_copy_msb>( +                send_buff + get_send_frame_size()*i, (*send_info) + i, +                get_send_frame_size(), _fd +            )); +        } +    } + +    ~e100_mmap_zero_copy_impl(void){ +        UHD_LOG << "cleanup: munmap" << std::endl; +        ::munmap(_mapped_mem, _map_size); +    } + +    managed_recv_buffer::sptr get_recv_buff(double timeout){ +        if (fp_verbose) UHD_LOGV(always) << "get_recv_buff: " << _recv_index << std::endl; +        e100_mmap_zero_copy_mrb &mrb = *_mrb_pool[_recv_index]; + +        //poll/wait for a ready frame +        if (not mrb.ready()){ +            for (size_t i = 0; i < poll_breakout; i++){ +                pollfd pfd; +                pfd.fd = _fd; +                pfd.events = POLLIN; +                ssize_t poll_ret = ::poll(&pfd, 1, size_t(timeout*1e3/poll_breakout)); +                if (fp_verbose) UHD_LOGV(always) << "  POLLIN: " << poll_ret << std::endl; +                if (poll_ret > 0) goto found_user_frame; //good poll, continue on +            } +            return managed_recv_buffer::sptr(); //timed-out for real +        } found_user_frame: + +        //increment the index for the next call +        if (++_recv_index == get_num_recv_frames()) _recv_index = 0; + +        //return the managed buffer for this frame +        return mrb.get_new(); +    } + +    size_t get_num_recv_frames(void) const{ +        return _rb_size.num_rx_frames; +    } + +    size_t get_recv_frame_size(void) const{ +        return _frame_size; +    } + +    managed_send_buffer::sptr get_send_buff(double timeout){ +        if (fp_verbose) UHD_LOGV(always) << "get_send_buff: " << _send_index << std::endl; +        e100_mmap_zero_copy_msb &msb = *_msb_pool[_send_index]; + +        //poll/wait for a ready frame +        if (not msb.ready()){ +            pollfd pfd; +            pfd.fd = _fd; +            pfd.events = POLLOUT; +            ssize_t poll_ret = ::poll(&pfd, 1, size_t(timeout*1e3)); +            if (fp_verbose) UHD_LOGV(always) << "  POLLOUT: " << poll_ret << std::endl; +            if (poll_ret <= 0) return managed_send_buffer::sptr(); +        } + +        //increment the index for the next call +        if (++_send_index == get_num_send_frames()) _send_index = 0; + +        //return the managed buffer for this frame +        return msb.get_new(); +    } + +    size_t get_num_send_frames(void) const{ +        return _rb_size.num_tx_frames; +    } + +    size_t get_send_frame_size(void) const{ +        return _frame_size; +    } + +private: +    //file descriptor for mmap +    int _fd; + +    //the mapped memory itself +    void *_mapped_mem; + +    //mapped memory sizes +    usrp_e_ring_buffer_size_t _rb_size; +    size_t _frame_size, _map_size; + +    //re-usable managed buffers +    std::vector<boost::shared_ptr<e100_mmap_zero_copy_mrb> > _mrb_pool; +    std::vector<boost::shared_ptr<e100_mmap_zero_copy_msb> > _msb_pool; + +    //indexes into sub-sections of mapped memory +    size_t _recv_index, _send_index; +}; + +/*********************************************************************** + * The zero copy interface make function + **********************************************************************/ +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 new file mode 100644 index 000000000..75be2cfbe --- /dev/null +++ b/host/lib/usrp/e100/e100_regs.hpp @@ -0,0 +1,137 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +//////////////////////////////////////////////////////////////// +// +//         Memory map for embedded wishbone bus +// +//////////////////////////////////////////////////////////////// + +// All addresses are byte addresses.  All accesses are word (16-bit) accesses. +//  This means that address bit 0 is usually 0. +//  There are 11 bits of address for the control. + +#ifndef INCLUDED_E100_REGS_HPP +#define INCLUDED_E100_REGS_HPP + +///////////////////////////////////////////////////// +// Slave pointers + +#define E100_REG_SLAVE(n) ((n)<<7) + +///////////////////////////////////////////////////// +// Slave 0 -- Misc Regs + +#define E100_REG_MISC_BASE E100_REG_SLAVE(0) + +#define E100_REG_MISC_LED        E100_REG_MISC_BASE + 0 +#define E100_REG_MISC_SW         E100_REG_MISC_BASE + 2 +#define E100_REG_MISC_CGEN_CTRL  E100_REG_MISC_BASE + 4 +#define E100_REG_MISC_CGEN_ST    E100_REG_MISC_BASE + 6 +#define E100_REG_MISC_TEST       E100_REG_MISC_BASE + 8 +#define E100_REG_MISC_RX_LEN     E100_REG_MISC_BASE + 10 +#define E100_REG_MISC_TX_LEN     E100_REG_MISC_BASE + 12 +#define E100_REG_MISC_XFER_RATE  E100_REG_MISC_BASE + 14 + +///////////////////////////////////////////////////// +// Slave 1 -- UART +//   CLKDIV is 16 bits, others are only 8 + +#define E100_REG_UART_BASE E100_REG_SLAVE(1) + +#define E100_REG_UART_CLKDIV  E100_REG_UART_BASE + 0 +#define E100_REG_UART_TXLEVEL E100_REG_UART_BASE + 2 +#define E100_REG_UART_RXLEVEL E100_REG_UART_BASE + 4 +#define E100_REG_UART_TXCHAR  E100_REG_UART_BASE + 6 +#define E100_REG_UART_RXCHAR  E100_REG_UART_BASE + 8 + +///////////////////////////////////////////////////// +// Slave 2 -- SPI Core +//these are 32-bit registers mapped onto the 16-bit Wishbone bus. +//Using peek32/poke32 should allow transparent use of these registers. +#define E100_REG_SPI_BASE E100_REG_SLAVE(2) + +//spi slave constants +#define UE_SPI_SS_AD9522    (1 << 3) +#define UE_SPI_SS_AD9862    (1 << 2) +#define UE_SPI_SS_TX_DB     (1 << 1) +#define UE_SPI_SS_RX_DB     (1 << 0) + +//////////////////////////////////////////////// +// Slave 3 -- I2C Core + +#define E100_REG_I2C_BASE E100_REG_SLAVE(3) + +//////////////////////////////////////////////// +// Slave 5 -- Error messages buffer + +#define E100_REG_ERR_BUFF E100_REG_SLAVE(5) + +/////////////////////////////////////////////////// +// Slave 7 -- Readback Mux 32 + +#define E100_REG_RB_MUX_32_BASE  E100_REG_SLAVE(7) + +#define E100_REG_RB_TIME_NOW_HI     E100_REG_RB_MUX_32_BASE + 0 +#define E100_REG_RB_TIME_NOW_LO     E100_REG_RB_MUX_32_BASE + 4 +#define E100_REG_RB_TIME_PPS_HI     E100_REG_RB_MUX_32_BASE + 8 +#define E100_REG_RB_TIME_PPS_LO     E100_REG_RB_MUX_32_BASE + 12 +#define E100_REG_RB_MISC_TEST32     E100_REG_RB_MUX_32_BASE + 16 +#define E100_REG_RB_ERR_STATUS      E100_REG_RB_MUX_32_BASE + 20 +#define E100_REG_RB_COMPAT          E100_REG_RB_MUX_32_BASE + 24 +#define E100_REG_RB_GPIO            E100_REG_RB_MUX_32_BASE + 28 + +//////////////////////////////////////////////////// +// Slave 8 -- Settings Bus +// +// Output-only, no readback, 64 registers total +//  Each register must be written 64 bits at a time +//  First the address xxx_xx00 and then xxx_xx10 + +// 64 total regs in address space +#define UE_SR_RX_CTRL0 0       // 9 regs (+0 to +8) +#define UE_SR_RX_DSP0 10       // 4 regs (+0 to +3) +#define UE_SR_RX_CTRL1 16      // 9 regs (+0 to +8) +#define UE_SR_RX_DSP1 26       // 4 regs (+0 to +3) +#define UE_SR_ERR_CTRL 30      // 1 reg +#define UE_SR_TX_CTRL 32       // 4 regs (+0 to +3) +#define UE_SR_TX_DSP 38        // 3 regs (+0 to +2) + +#define UE_SR_TIME64 42        // 6 regs (+0 to +5) +#define UE_SR_RX_FRONT 48      // 5 regs (+0 to +4) +#define UE_SR_TX_FRONT 54      // 5 regs (+0 to +4) + +#define UE_SR_REG_TEST32 60    // 1 reg +#define UE_SR_CLEAR_FIFO 61    // 1 reg +#define UE_SR_GLOBAL_RESET 63  // 1 reg +#define UE_SR_USER_REGS 64     // 2 regs + +#define UE_SR_GPIO 128 + +#define E100_REG_SR_ADDR(n) (E100_REG_SLAVE(8) + (4*(n))) + +#define E100_REG_SR_MISC_TEST32        E100_REG_SR_ADDR(UE_SR_REG_TEST32) +#define E100_REG_SR_ERR_CTRL           E100_REG_SR_ADDR(UE_SR_ERR_CTRL) + +///////////////////////////////////////////////// +// Magic reset regs +//////////////////////////////////////////////// +#define E100_REG_CLEAR_FIFO         E100_REG_SR_ADDR(UE_SR_CLEAR_FIFO) +#define E100_REG_GLOBAL_RESET       E100_REG_SR_ADDR(UE_SR_GLOBAL_RESET) + +#endif + diff --git a/host/lib/usrp/e100/fpga_downloader.cpp b/host/lib/usrp/e100/fpga_downloader.cpp new file mode 100644 index 000000000..7074c8299 --- /dev/null +++ b/host/lib/usrp/e100/fpga_downloader.cpp @@ -0,0 +1,272 @@ +// +// 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> +#ifdef UHD_DLL_EXPORTS +#include <uhd/exception.hpp> +#include <uhd/utils/msg.hpp> +#else //special case when this file is externally included +#include <stdexcept> +#include <iostream> +#define UHD_MSG(type) std::cout +namespace uhd{ +    typedef std::runtime_error os_error; +    typedef std::runtime_error io_error; +} +#endif + +#include <sstream> +#include <fstream> +#include <string> +#include <cstdlib> + +#include <fcntl.h> +#include <sys/types.h> +#include <sys/stat.h> +#include <sys/ioctl.h> + +#include <linux/spi/spidev.h> + +/* + * Configuration connections + * + * CCK    - MCSPI1_CLK + * DIN    - MCSPI1_MOSI + * PROG_B - GPIO_175     - output (change mux) + * DONE   - GPIO_173     - input  (change mux) + * INIT_B - GPIO_114     - input  (change mux) + * +*/ + +namespace usrp_e_fpga_downloader_utility{ + +const unsigned int PROG_B = 175; +const unsigned int DONE   = 173; +const unsigned int INIT_B = 114; + +//static std::string bit_file = "safe_u1e.bin"; + +const int BUF_SIZE = 4096; + +enum gpio_direction {IN, OUT}; + +class gpio { +	public: + +	gpio(unsigned int gpio_num, gpio_direction pin_direction); + +	bool get_value(); +	void set_value(bool state); + +	private: + +	std::stringstream base_path; +	std::fstream value_file;	 +}; + +class spidev { +	public: + +	spidev(std::string dev_name); +	~spidev(); + +	void send(char *wbuf, char *rbuf, unsigned int nbytes); + +	private: + +	int fd; + +}; + +gpio::gpio(unsigned int gpio_num, gpio_direction pin_direction) +{ +	std::fstream export_file; + +	export_file.open("/sys/class/gpio/export", std::ios::out); +	if (not export_file.is_open()) throw uhd::os_error( +		"Failed to open gpio export file." +	); + +	export_file << gpio_num << std::endl; + +	base_path << "/sys/class/gpio/gpio" << gpio_num << std::flush; + +	std::fstream direction_file; +	std::string direction_file_name; + +	if (gpio_num != 114) { +		direction_file_name = base_path.str() + "/direction"; + +		direction_file.open(direction_file_name.c_str()); +		if (!direction_file.is_open()) throw uhd::os_error( +			"Failed to open direction file." +		); +		if (pin_direction == OUT) +			direction_file << "out" << std::endl; +		else +			direction_file << "in" << std::endl; +	} + +	std::string value_file_name; + +	value_file_name = base_path.str() + "/value"; + +	value_file.open(value_file_name.c_str(), std::ios_base::in | std::ios_base::out); +	if (!value_file.is_open()) throw uhd::os_error( +		"Failed to open value file." +	); +} + +bool gpio::get_value() +{ + +	std::string val; + +	std::getline(value_file, val); +	value_file.seekg(0); + +	if (val == "0") +		return false; +	else if (val == "1") +		return true; +	else +		throw uhd::os_error("Data read from value file|" + val + "|"); + +	return false; +} + +void gpio::set_value(bool state) +{ + +	if (state) +		value_file << "1" << std::endl; +	else +		value_file << "0" << std::endl; +} + +static void prepare_fpga_for_configuration(gpio &prog, gpio &)//init) +{ + +	prog.set_value(true); +	prog.set_value(false); +	prog.set_value(true); + +#if 0 +	bool ready_to_program(false); +	unsigned int count(0); +	do { +		ready_to_program = init.get_value(); +		count++; + +		sleep(1); +	} while (count < 10 && !ready_to_program); + +	if (count == 10) { +		throw uhd::os_error("FPGA not ready for programming."); +	} +#endif +} + +spidev::spidev(std::string fname) +{ +	int ret; +	int mode = 0; +	int speed = 12000000; +	int bits = 8; + +	fd = open(fname.c_str(), O_RDWR); + +	ret = ioctl(fd, SPI_IOC_WR_MODE, &mode); +	ret = ioctl(fd, SPI_IOC_WR_MAX_SPEED_HZ, &speed); +	ret = ioctl(fd, SPI_IOC_WR_BITS_PER_WORD, &bits); +} +	 + +spidev::~spidev() +{ +	close(fd); +} + +void spidev::send(char *buf, char *rbuf, unsigned int nbytes) +{ +	int ret; + +	struct spi_ioc_transfer tr; +	tr.tx_buf = (unsigned long) buf; +	tr.rx_buf = (unsigned long) rbuf; +	tr.len = nbytes; +	tr.delay_usecs = 0; +	tr.speed_hz = 48000000; +	tr.bits_per_word = 8; + +	ret = ioctl(fd, SPI_IOC_MESSAGE(1), &tr);	 + +} + +static void send_file_to_fpga(const std::string &file_name, gpio &error, gpio &done) +{ +	std::ifstream bitstream; + +	bitstream.open(file_name.c_str(), std::ios::binary); +	if (!bitstream.is_open()) throw uhd::os_error( +		"Coult not open the file: " + file_name +	); + +	spidev spi("/dev/spidev1.0"); +	char buf[BUF_SIZE]; +	char rbuf[BUF_SIZE]; + +	do { +		bitstream.read(buf, BUF_SIZE); +		spi.send(buf, rbuf, bitstream.gcount()); + +		if (error.get_value()) +			throw uhd::os_error("INIT_B went high, error occured."); + +		if (!done.get_value()) +			UHD_MSG(status) << "Configuration complete." << std::endl; + +	} while (bitstream.gcount() == BUF_SIZE); +} + +}//namespace usrp_e_fpga_downloader_utility + +void e100_load_fpga(const std::string &bin_file){ +	using namespace usrp_e_fpga_downloader_utility; + +	gpio gpio_prog_b(PROG_B, OUT); +	gpio gpio_init_b(INIT_B, IN); +	gpio gpio_done  (DONE,   IN); + +	UHD_MSG(status) << "Loading FPGA image: " << bin_file << "... " << std::flush; + +//	if(std::system("/sbin/rmmod usrp_e") != 0){ +//		UHD_MSG(warning) << "USRP-E100 FPGA downloader: could not unload usrp_e module" << std::endl; +//	} + +	prepare_fpga_for_configuration(gpio_prog_b, gpio_init_b); + +	UHD_MSG(status) << "done = " << gpio_done.get_value() << std::endl; + +	send_file_to_fpga(bin_file, gpio_init_b, gpio_done); + +//	if(std::system("/sbin/modprobe usrp_e") != 0){ +//		UHD_MSG(warning) << "USRP-E100 FPGA downloader: could not load usrp_e module" << std::endl; +//	} + +} + diff --git a/host/lib/usrp/e100/include/linux/usrp_e.h b/host/lib/usrp/e100/include/linux/usrp_e.h new file mode 100644 index 000000000..37e9ee31a --- /dev/null +++ b/host/lib/usrp/e100/include/linux/usrp_e.h @@ -0,0 +1,60 @@ + +/* + *  Copyright (C) 2010 Ettus Research, LLC + * + *  Written by Philip Balister <philip@opensdr.com> + * + *  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 2 of the License, or + *  (at your option) any later version. + */ + +#ifndef __USRP_E_H +#define __USRP_E_H + +#include <linux/types.h> +#include <linux/ioctl.h> + +struct usrp_e_ctl16 { +	__u32 offset; +	__u32 count; +	__u16 buf[20]; +}; + +struct usrp_e_ctl32 { +	__u32 offset; +	__u32 count; +	__u32 buf[10]; +}; + +#define USRP_E_IOC_MAGIC	'u' +#define USRP_E_WRITE_CTL16	_IOW(USRP_E_IOC_MAGIC, 0x20, struct usrp_e_ctl16) +#define USRP_E_READ_CTL16	_IOWR(USRP_E_IOC_MAGIC, 0x21, struct usrp_e_ctl16) +#define USRP_E_WRITE_CTL32	_IOW(USRP_E_IOC_MAGIC, 0x22, struct usrp_e_ctl32) +#define USRP_E_READ_CTL32	_IOWR(USRP_E_IOC_MAGIC, 0x23, struct usrp_e_ctl32) +#define USRP_E_GET_RB_INFO      _IOR(USRP_E_IOC_MAGIC, 0x27, struct usrp_e_ring_buffer_size_t) +#define USRP_E_GET_COMPAT_NUMBER _IO(USRP_E_IOC_MAGIC, 0x28) + +#define USRP_E_COMPAT_NUMBER 3 + +/* Flag defines */ +#define RB_USER (1<<0) +#define RB_KERNEL (1<<1) +#define RB_OVERRUN (1<<2) +#define RB_DMA_ACTIVE (1<<3) +#define RB_USER_PROCESS (1<<4) + +struct ring_buffer_info { +	int flags; +	int len; +}; + +struct usrp_e_ring_buffer_size_t { +	int num_pages_rx_flags; +	int num_rx_frames; +	int num_pages_tx_flags; +	int num_tx_frames; +}; + +#endif diff --git a/host/lib/usrp/e100/io_impl.cpp b/host/lib/usrp/e100/io_impl.cpp new file mode 100644 index 000000000..e9608125f --- /dev/null +++ b/host/lib/usrp/e100/io_impl.cpp @@ -0,0 +1,366 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "recv_packet_demuxer.hpp" +#include "validate_subdev_spec.hpp" +#include "async_packet_handler.hpp" +#include "../../transport/super_recv_packet_handler.hpp" +#include "../../transport/super_send_packet_handler.hpp" +#include <linux/usrp_e.h> //ioctl structures and constants +#include "e100_impl.hpp" +#include "e100_regs.hpp" +#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp> +#include <uhd/utils/tasks.hpp> +#include <uhd/utils/thread_priority.hpp> +#include <uhd/transport/bounded_buffer.hpp> +#include <boost/bind.hpp> +#include <boost/format.hpp> +#include <boost/bind.hpp> +#include <boost/thread/thread.hpp> +#include <poll.h> //poll +#include <fcntl.h> //open, close +#include <sstream> +#include <fstream> +#include <boost/make_shared.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; + +/*********************************************************************** + * io impl details (internal to this file) + * - pirate crew of 1 + * - bounded buffer + * - thread loop + * - vrt packet handler states + **********************************************************************/ +struct e100_impl::io_impl{ +    io_impl(void): +        false_alarm(0), async_msg_fifo(1000/*messages deep*/) +    { /* NOP */ } + +    double tick_rate; //set by update tick rate method +    e100_ctrl::sptr iface; //so handle irq can peek and poke +    void handle_irq(void); +    size_t false_alarm; +    //The data transport is listed first so that it is deconstructed last, +    //which is after the states and booty which may hold managed buffers. +    recv_packet_demuxer::sptr demuxer; + +    //a pirate's life is the life for me! +    void recv_pirate_loop( +        spi_iface::sptr //keep a sptr to iface which shares gpio147 +    ){ +        //open the GPIO and set it up for an IRQ +        std::ofstream edge_file("/sys/class/gpio/gpio147/edge"); +        edge_file << "rising" << std::endl << std::flush; +        edge_file.close(); +        int fd = ::open("/sys/class/gpio/gpio147/value", O_RDONLY); +        if (fd < 0) UHD_MSG(error) << "Unable to open GPIO for IRQ\n"; + +        while (not boost::this_thread::interruption_requested()){ +            pollfd pfd; +            pfd.fd = fd; +            pfd.events = POLLPRI | POLLERR; +            ssize_t ret = ::poll(&pfd, 1, 100/*ms*/); +            if (ret > 0) this->handle_irq(); +        } + +        //cleanup before thread exit +        ::close(fd); +    } +    bounded_buffer<async_metadata_t> async_msg_fifo; +    task::sptr pirate_task; +}; + +void e100_impl::io_impl::handle_irq(void){ +    //check the status of the async msg buffer +    const boost::uint32_t status = iface->peek32(E100_REG_RB_ERR_STATUS); +    if ((status & 0x3) == 0){ //not done or error +        //This could be a false-alarm because spi readback is mixed in. +        //So we just sleep for a bit rather than interrupt continuously. +        if (false_alarm++ > 3) boost::this_thread::sleep(boost::posix_time::milliseconds(1)); +        return; +    } +    false_alarm = 0; //its a real message, reset the count... +    //std::cout << boost::format("status: 0x%x") % status << std::endl; + +    //load the data struct and call the ioctl +    usrp_e_ctl32 data; +    data.offset = E100_REG_ERR_BUFF; +    data.count = status >> 16; +    iface->ioctl(USRP_E_READ_CTL32, &data); +    //for (size_t i = 0; i < data.count; i++){ +        //data.buf[i] = iface->peek32(E100_REG_ERR_BUFF + i*sizeof(boost::uint32_t)); +        //std::cout << boost::format("    buff[%u] = 0x%08x\n") % i % data.buf[i]; +    //} + +    //unpack the vrt header and process below... +    vrt::if_packet_info_t if_packet_info; +    if_packet_info.num_packet_words32 = data.count; +    try{vrt::if_hdr_unpack_le(data.buf, if_packet_info);} +    catch(const std::exception &e){ +        UHD_MSG(error) << "Error unpacking vrt header:\n" << e.what() << std::endl; +        goto prepare; +    } + +    //handle a tx async report message +    if (if_packet_info.sid == E100_TX_ASYNC_SID and if_packet_info.packet_type != vrt::if_packet_info_t::PACKET_TYPE_DATA){ + +        //fill in the async metadata +        async_metadata_t metadata; +        load_metadata_from_buff(uhd::wtohx<boost::uint32_t>, metadata, if_packet_info, data.buf, tick_rate); + +        //push the message onto the queue +        async_msg_fifo.push_with_pop_on_full(metadata); + +        //print some fastpath messages +        standard_async_msg_prints(metadata); +    } + +    //prepare for the next round +    prepare: +    iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 0); //clear +    while ((iface->peek32(E100_REG_RB_ERR_STATUS) & (1 << 2)) == 0){} //wait for idle +    iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 1); //start +} + +/*********************************************************************** + * Helper Functions + **********************************************************************/ +void e100_impl::io_init(void){ + +    //create new io impl +    _io_impl = UHD_PIMPL_MAKE(io_impl, ()); +    _io_impl->demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), E100_RX_SID_BASE); +    _io_impl->iface = _fpga_ctrl; + +    //clear fifo state machines +    _fpga_ctrl->poke32(E100_REG_CLEAR_FIFO, 0); + +    //allocate streamer weak ptrs containers +    _rx_streamers.resize(_rx_dsps.size()); +    _tx_streamers.resize(1/*known to be 1 dsp*/); + +    //prepare the async msg buffer for incoming messages +    _fpga_ctrl->poke32(E100_REG_SR_ERR_CTRL, 1 << 0); //clear +    while ((_fpga_ctrl->peek32(E100_REG_RB_ERR_STATUS) & (1 << 2)) == 0){} //wait for idle +    _fpga_ctrl->poke32(E100_REG_SR_ERR_CTRL, 1 << 1); //start + +    //spawn a pirate, yarrr! +    _io_impl->pirate_task = task::make(boost::bind( +        &e100_impl::io_impl::recv_pirate_loop, _io_impl.get(), _aux_spi_iface +    )); +} + +void e100_impl::update_tick_rate(const double rate){ +    _io_impl->tick_rate = rate; + +    //update the tick rate on all existing streamers -> thread safe +    for (size_t i = 0; i < _rx_streamers.size(); i++){ +        boost::shared_ptr<sph::recv_packet_streamer> my_streamer = +            boost::dynamic_pointer_cast<sph::recv_packet_streamer>(_rx_streamers[i].lock()); +        if (my_streamer.get() == NULL) continue; +        my_streamer->set_tick_rate(rate); +    } +    for (size_t i = 0; i < _tx_streamers.size(); i++){ +        boost::shared_ptr<sph::send_packet_streamer> my_streamer = +            boost::dynamic_pointer_cast<sph::send_packet_streamer>(_tx_streamers[i].lock()); +        if (my_streamer.get() == NULL) continue; +        my_streamer->set_tick_rate(rate); +    } +} + +void e100_impl::update_rx_samp_rate(const size_t dspno, const double rate){ +    boost::shared_ptr<sph::recv_packet_streamer> my_streamer = +        boost::dynamic_pointer_cast<sph::recv_packet_streamer>(_rx_streamers[dspno].lock()); +    if (my_streamer.get() == NULL) return; + +    my_streamer->set_samp_rate(rate); +    const double adj = _rx_dsps[dspno]->get_scaling_adjustment(); +    my_streamer->set_scale_factor(adj); +} + +void e100_impl::update_tx_samp_rate(const size_t dspno, const double rate){ +    boost::shared_ptr<sph::send_packet_streamer> my_streamer = +        boost::dynamic_pointer_cast<sph::send_packet_streamer>(_tx_streamers[dspno].lock()); +    if (my_streamer.get() == NULL) return; + +    my_streamer->set_samp_rate(rate); +    const double adj = _tx_dsp->get_scaling_adjustment(); +    my_streamer->set_scale_factor(adj); +} + +void e100_impl::update_rates(void){ +    const fs_path mb_path = "/mboards/0"; +    _tree->access<double>(mb_path / "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(mb_path / "rx_dsps")){ +        _tree->access<double>(mb_path / "rx_dsps" / name / "rate" / "value").update(); +    } +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +        _tree->access<double>(mb_path / "tx_dsps" / name / "rate" / "value").update(); +    } +} + +void e100_impl::update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){ +    fs_path 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); +} + +void e100_impl::update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){ +    fs_path 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); +} + +/*********************************************************************** + * Async Recv + **********************************************************************/ +bool e100_impl::recv_async_msg( +    async_metadata_t &async_metadata, double timeout +){ +    boost::this_thread::disable_interruption di; //disable because the wait can throw +    return _io_impl->async_msg_fifo.pop_with_timed_wait(async_metadata, timeout); +} + +/*********************************************************************** + * Receive streamer + **********************************************************************/ +rx_streamer::sptr e100_impl::get_rx_stream(const uhd::stream_args_t &args_){ +    stream_args_t args = args_; + +    //setup defaults for unspecified values +    args.otw_format = args.otw_format.empty()? "sc16" : args.otw_format; +    args.channels = args.channels.empty()? std::vector<size_t>(1, 0) : args.channels; + +    //calculate packet size +    static const size_t hdr_size = 0 +        + vrt::max_if_hdr_words32*sizeof(boost::uint32_t) +        + sizeof(vrt::if_packet_info_t().tlr) //forced to have trailer +        - sizeof(vrt::if_packet_info_t().cid) //no class id ever used +        - sizeof(vrt::if_packet_info_t().tsi) //no int time ever used +    ; +    const size_t bpp = _data_transport->get_recv_frame_size() - hdr_size; +    const size_t bpi = convert::get_bytes_per_item(args.otw_format); +    const size_t spp = unsigned(args.args.cast<double>("spp", bpp/bpi)); + +    //make the new streamer given the samples per packet +    boost::shared_ptr<sph::recv_packet_streamer> my_streamer = boost::make_shared<sph::recv_packet_streamer>(spp); + +    //init some streamer stuff +    my_streamer->resize(args.channels.size()); +    my_streamer->set_vrt_unpacker(&vrt::if_hdr_unpack_le); + +    //set the converter +    uhd::convert::id_type id; +    id.input_format = args.otw_format + "_item32_le"; +    id.num_inputs = 1; +    id.output_format = args.cpu_format; +    id.num_outputs = 1; +    my_streamer->set_converter(id); + +    //bind callbacks for the handler +    for (size_t chan_i = 0; chan_i < args.channels.size(); chan_i++){ +        const size_t dsp = args.channels[chan_i]; +        _rx_dsps[dsp]->set_nsamps_per_packet(spp); //seems to be a good place to set this +        _rx_dsps[dsp]->setup(args); +        my_streamer->set_xport_chan_get_buff(chan_i, boost::bind( +            &recv_packet_demuxer::get_recv_buff, _io_impl->demuxer, dsp, _1 +        ), true /*flush*/); +        my_streamer->set_overflow_handler(chan_i, boost::bind( +            &rx_dsp_core_200::handle_overflow, _rx_dsps[dsp] +        )); +        _rx_streamers[dsp] = my_streamer; //store weak pointer +    } + +    //sets all tick and samp rates on this streamer +    this->update_rates(); + +    return my_streamer; +} + +/*********************************************************************** + * Transmit streamer + **********************************************************************/ +tx_streamer::sptr e100_impl::get_tx_stream(const uhd::stream_args_t &args_){ +    stream_args_t args = args_; + +    //setup defaults for unspecified values +    args.otw_format = args.otw_format.empty()? "sc16" : args.otw_format; +    args.channels = args.channels.empty()? std::vector<size_t>(1, 0) : args.channels; + +    //calculate packet size +    static const size_t hdr_size = 0 +        + vrt::max_if_hdr_words32*sizeof(boost::uint32_t) +        + sizeof(vrt::if_packet_info_t().tlr) //forced to have trailer +        - sizeof(vrt::if_packet_info_t().sid) //no stream id ever used +        - sizeof(vrt::if_packet_info_t().cid) //no class id ever used +        - sizeof(vrt::if_packet_info_t().tsi) //no int time ever used +    ; +    static const size_t bpp = _data_transport->get_send_frame_size() - hdr_size; +    const size_t spp = bpp/convert::get_bytes_per_item(args.otw_format); + +    //make the new streamer given the samples per packet +    boost::shared_ptr<sph::send_packet_streamer> my_streamer = boost::make_shared<sph::send_packet_streamer>(spp); + +    //init some streamer stuff +    my_streamer->resize(args.channels.size()); +    my_streamer->set_vrt_packer(&vrt::if_hdr_pack_le); + +    //set the converter +    uhd::convert::id_type id; +    id.input_format = args.cpu_format; +    id.num_inputs = 1; +    id.output_format = args.otw_format + "_item32_le"; +    id.num_outputs = 1; +    my_streamer->set_converter(id); + +    //bind callbacks for the handler +    for (size_t chan_i = 0; chan_i < args.channels.size(); chan_i++){ +        const size_t dsp = args.channels[chan_i]; +        UHD_ASSERT_THROW(dsp == 0); //always 0 +        _tx_dsp->setup(args); +        my_streamer->set_xport_chan_get_buff(chan_i, boost::bind( +            &zero_copy_if::get_send_buff, _data_transport, _1 +        )); +        _tx_streamers[dsp] = my_streamer; //store weak pointer +    } + +    //sets all tick and samp rates on this streamer +    this->update_rates(); + +    return my_streamer; +} diff --git a/host/lib/usrp/gps_ctrl.cpp b/host/lib/usrp/gps_ctrl.cpp new file mode 100644 index 000000000..f3bdded60 --- /dev/null +++ b/host/lib/usrp/gps_ctrl.cpp @@ -0,0 +1,271 @@ +// +// 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/gps_ctrl.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/exception.hpp> +#include <uhd/types/sensors.hpp> +#include <boost/algorithm/string.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/cstdint.hpp> +#include <boost/date_time/posix_time/posix_time.hpp> +#include <boost/thread/thread.hpp> +#include <boost/tokenizer.hpp> +#include <boost/format.hpp> + +using namespace uhd; +using namespace boost::gregorian; +using namespace boost::posix_time; +using namespace boost::algorithm; +using namespace boost::this_thread; + +/*! + * A GPS control for Jackson Labs devices (and other NMEA compatible GPS's) + */ + +class gps_ctrl_impl : public gps_ctrl{ +public: +  gps_ctrl_impl(uart_iface::sptr uart){ +    _uart = uart; + +    std::string reply; +    bool i_heard_some_nmea = false, i_heard_something_weird = false; +    gps_type = GPS_TYPE_NONE; +     +    //first we look for a Jackson Labs Firefly (since that's what we provide...) +    _flush(); //get whatever junk is in the rx buffer right now, and throw it away +    _send("HAAAY GUYYYYS\n"); //to elicit a response from the Firefly + +    //wait for _send(...) to return +    sleep(milliseconds(FIREFLY_STUPID_DELAY_MS)); + +    //then we loop until we either timeout, or until we get a response that indicates we're a JL device +    const boost::system_time comm_timeout = boost::get_system_time() + milliseconds(GPS_COMM_TIMEOUT_MS); +    while(boost::get_system_time() < comm_timeout) { +      reply = _recv(); +      if(reply.find("Command Error") != std::string::npos) { +        gps_type = GPS_TYPE_JACKSON_LABS; +        break; +      }  +      else if(reply.substr(0, 3) == "$GP") i_heard_some_nmea = true; //but keep looking for that "Command Error" response +      else if(reply.length() != 0) i_heard_something_weird = true; //probably wrong baud rate +      sleep(milliseconds(GPS_TIMEOUT_DELAY_MS)); +    } + +    if((i_heard_some_nmea) && (gps_type != GPS_TYPE_JACKSON_LABS)) gps_type = GPS_TYPE_GENERIC_NMEA; + +    if((gps_type == GPS_TYPE_NONE) && i_heard_something_weird) { +      UHD_MSG(error) << "GPS invalid reply \"" << reply << "\", assuming none available" << std::endl; +    } + +    switch(gps_type) { +    case GPS_TYPE_JACKSON_LABS: +      UHD_MSG(status) << "Found a Jackson Labs GPS" << std::endl; +      init_firefly(); +      break; + +    case GPS_TYPE_GENERIC_NMEA: +      if(gps_type == GPS_TYPE_GENERIC_NMEA) UHD_MSG(status) << "Found a generic NMEA GPS device" << std::endl; +      break; + +    case GPS_TYPE_NONE: +    default: +      break; + +    } +  } + +  ~gps_ctrl_impl(void){ +    /* NOP */ +  } + +  //return a list of supported sensors +  std::vector<std::string> get_sensors(void) { +    std::vector<std::string> ret = boost::assign::list_of +        ("gps_gpgga") +        ("gps_gprmc") +        ("gps_time") +        ("gps_locked"); +    return ret; +  } + +  uhd::sensor_value_t get_sensor(std::string key) { +    if(key == "gps_gpgga" +    or key == "gps_gprmc") { +        return sensor_value_t( +                 boost::to_upper_copy(key), +                 get_nmea(boost::to_upper_copy(key.substr(4,8))), +                 ""); +    } +    else if(key == "gps_time") { +        return sensor_value_t("GPS epoch time", int(get_epoch_time()), "seconds"); +    } +    else if(key == "gps_locked") { +        return sensor_value_t("GPS lock status", locked(), "locked", "unlocked"); +    } +    else { +        throw uhd::value_error("gps ctrl get_sensor unknown key: " + key); +    } +  } + +private: +  void init_firefly(void) { +    //issue some setup stuff so it spits out the appropriate data +    //none of these should issue replies so we don't bother looking for them +    //we have to sleep between commands because the JL device, despite not acking, takes considerable time to process each command. +     sleep(milliseconds(FIREFLY_STUPID_DELAY_MS)); +    _send("SYST:COMM:SER:ECHO OFF\n"); +     sleep(milliseconds(FIREFLY_STUPID_DELAY_MS)); +    _send("SYST:COMM:SER:PRO OFF\n"); +     sleep(milliseconds(FIREFLY_STUPID_DELAY_MS)); +    _send("GPS:GPGGA 1\n"); +     sleep(milliseconds(FIREFLY_STUPID_DELAY_MS)); +    _send("GPS:GGAST 0\n"); +     sleep(milliseconds(FIREFLY_STUPID_DELAY_MS)); +    _send("GPS:GPRMC 1\n"); +     sleep(milliseconds(FIREFLY_STUPID_DELAY_MS)); +  } +  +  //retrieve a raw NMEA sentence +  std::string get_nmea(std::string msgtype) { +    msgtype.insert(0, "$"); +    std::string reply; +    if(not gps_detected()) { +        UHD_MSG(error) << "get_nmea(): unsupported GPS or no GPS detected"; +        return std::string(); +    } + +    _flush(); //flush all input before waiting for a message + +    const boost::system_time comm_timeout = boost::get_system_time() + milliseconds(GPS_COMM_TIMEOUT_MS); +    while(boost::get_system_time() < comm_timeout) { +        reply = _recv(); +        if(reply.substr(0, 6) == msgtype) +          return reply; +        boost::this_thread::sleep(milliseconds(GPS_TIMEOUT_DELAY_MS)); +    } +    throw uhd::value_error(str(boost::format("get_nmea(): no %s message found") % msgtype)); +    return std::string(); +  } + +  //helper function to retrieve a field from an NMEA sentence +  std::string get_token(std::string sentence, size_t offset) { +    boost::tokenizer<boost::escaped_list_separator<char> > tok(sentence); +    std::vector<std::string> toked; +    tok.assign(sentence); //this can throw +    toked.assign(tok.begin(), tok.end()); + +    if(toked.size() <= offset) { +        throw uhd::value_error(str(boost::format("Invalid response \"%s\"") % sentence)); +    } +    return toked[offset]; +  } + +  ptime get_time(void) { +    int error_cnt = 0; +    ptime gps_time; +    while(error_cnt < 3) { +        try { +            std::string reply = get_nmea("GPRMC"); + +            std::string datestr = get_token(reply, 9); +            std::string timestr = get_token(reply, 1); + +            if(datestr.size() == 0 or timestr.size() == 0) { +                throw uhd::value_error(str(boost::format("Invalid response \"%s\"") % reply)); +            } +             +            //just trust me on this one +            gps_time = ptime( date(  +                             greg_year(boost::lexical_cast<int>(datestr.substr(4, 2)) + 2000), +                             greg_month(boost::lexical_cast<int>(datestr.substr(2, 2))),  +                             greg_day(boost::lexical_cast<int>(datestr.substr(0, 2)))  +                           ), +                          hours(  boost::lexical_cast<int>(timestr.substr(0, 2))) +                        + minutes(boost::lexical_cast<int>(timestr.substr(2, 2))) +                        + seconds(boost::lexical_cast<int>(timestr.substr(4, 2))) +                     ); +            return gps_time; +             +        } catch(std::exception &e) { +            UHD_MSG(warning) << "get_time: " << e.what(); +            error_cnt++; +        } +    } +    throw uhd::value_error("Timeout after no valid message found"); +     +    return gps_time; //keep gcc from complaining +  } +   +  time_t get_epoch_time(void) { +      return (get_time() - from_time_t(0)).total_seconds(); +  } + +  bool gps_detected(void) { +    return (gps_type != GPS_TYPE_NONE); +  } + +  bool locked(void) { +    int error_cnt = 0; +    while(error_cnt < 3) { +        try { +            std::string reply = get_nmea("GPGGA"); +            if(reply.size() <= 1) return false; + +            return (get_token(reply, 6) != "0"); +        } catch(std::exception &e) { +            UHD_MSG(warning) << "locked: " << e.what(); +            error_cnt++; +        } +    } +    throw uhd::value_error("Timeout after no valid message found"); +    return false; +  } + +  uart_iface::sptr _uart; + +  void _flush(void){ +    while (not _uart->read_uart(0.0).empty()){ +        //NOP +    } +  } + +  std::string _recv(void){ +      return _uart->read_uart(GPS_TIMEOUT_DELAY_MS/1000.); +  } + +  void _send(const std::string &buf){ +      return _uart->write_uart(buf); +  } + +  enum { +    GPS_TYPE_JACKSON_LABS, +    GPS_TYPE_GENERIC_NMEA, +    GPS_TYPE_NONE +  } gps_type; + +  static const int GPS_COMM_TIMEOUT_MS = 1500; +  static const int GPS_TIMEOUT_DELAY_MS = 200; +  static const int FIREFLY_STUPID_DELAY_MS = 200; +}; + +/*********************************************************************** + * Public make function for the GPS control + **********************************************************************/ +gps_ctrl::sptr gps_ctrl::make(uart_iface::sptr uart){ +    return sptr(new gps_ctrl_impl(uart)); +} diff --git a/host/lib/usrp/mboard_eeprom.cpp b/host/lib/usrp/mboard_eeprom.cpp new file mode 100644 index 000000000..1f4abc27e --- /dev/null +++ b/host/lib/usrp/mboard_eeprom.cpp @@ -0,0 +1,462 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include <uhd/usrp/mboard_eeprom.hpp> +#include <uhd/types/mac_addr.hpp> +#include <uhd/utils/byteswap.hpp> +#include <boost/asio/ip/address_v4.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/lexical_cast.hpp> +#include <boost/foreach.hpp> +#include <algorithm> +#include <iostream> +#include <cstddef> + +using namespace uhd; +using namespace uhd::usrp; + +/*********************************************************************** + * Constants + **********************************************************************/ +static const size_t SERIAL_LEN = 9; +static const size_t NAME_MAX_LEN = 32 - SERIAL_LEN; + +/*********************************************************************** + * Utility functions + **********************************************************************/ + +//! A wrapper around std::copy that takes ranges instead of iterators. +template<typename RangeSrc, typename RangeDst> inline +void byte_copy(const RangeSrc &src, RangeDst &dst){ +    std::copy(boost::begin(src), boost::end(src), boost::begin(dst)); +} + +//! create a string from a byte vector, return empty if invalid ascii +static const std::string bytes_to_string(const byte_vector_t &bytes){ +    std::string out; +    BOOST_FOREACH(boost::uint8_t byte, bytes){ +        if (byte < 32 or byte > 127) return out; +        out += byte; +    } +    return out; +} + +//! create a byte vector from a string, null terminate unless max length +static const byte_vector_t string_to_bytes(const std::string &string, size_t max_length){ +    byte_vector_t bytes; +    for (size_t i = 0; i < std::min(string.size(), max_length); i++){ +        bytes.push_back(string[i]); +    } +    if (bytes.size() < max_length - 1) bytes.push_back('\0'); +    return bytes; +} + +//! convert a string to a byte vector to write to eeprom +static byte_vector_t string_to_uint16_bytes(const std::string &num_str){ +    const boost::uint16_t num = boost::lexical_cast<boost::uint16_t>(num_str); +    const byte_vector_t lsb_msb = boost::assign::list_of +        (boost::uint8_t(num >> 0))(boost::uint8_t(num >> 8)); +    return lsb_msb; +} + +//! convert a byte vector read from eeprom to a string +static std::string uint16_bytes_to_string(const byte_vector_t &bytes){ +    const boost::uint16_t num = (boost::uint16_t(bytes.at(0)) << 0) | (boost::uint16_t(bytes.at(1)) << 8); +    return (num == 0 or num == 0xffff)? "" : boost::lexical_cast<std::string>(num); +} + +/*********************************************************************** + * Implementation of N100 load/store + **********************************************************************/ +static const boost::uint8_t N100_EEPROM_ADDR = 0x50; + +struct n100_eeprom_map{ +    boost::uint16_t hardware; +    boost::uint8_t mac_addr[6]; +    boost::uint32_t subnet; +    boost::uint32_t ip_addr; +    boost::uint16_t _pad0; +    boost::uint16_t revision; +    boost::uint16_t product; +    unsigned char _pad1; +    unsigned char gpsdo; +    unsigned char serial[SERIAL_LEN]; +    unsigned char name[NAME_MAX_LEN]; +    boost::uint32_t gateway; +}; + +enum n200_gpsdo_type{ +    N200_GPSDO_NONE = 0, +    N200_GPSDO_INTERNAL = 1, +    N200_GPSDO_ONBOARD = 2 +}; + +static void load_n100(mboard_eeprom_t &mb_eeprom, i2c_iface &iface){ +    //extract the hardware number +    mb_eeprom["hardware"] = uint16_bytes_to_string( +        iface.read_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, hardware), 2) +    ); + +    //extract the revision number +    mb_eeprom["revision"] = uint16_bytes_to_string( +        iface.read_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, revision), 2) +    ); + +    //extract the product code +    mb_eeprom["product"] = uint16_bytes_to_string( +        iface.read_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, product), 2) +    ); + +    //extract the addresses +    mb_eeprom["mac-addr"] = mac_addr_t::from_bytes(iface.read_eeprom( +        N100_EEPROM_ADDR, offsetof(n100_eeprom_map, mac_addr), 6 +    )).to_string(); + +    boost::asio::ip::address_v4::bytes_type ip_addr_bytes; +    byte_copy(iface.read_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, ip_addr), 4), ip_addr_bytes); +    mb_eeprom["ip-addr"] = boost::asio::ip::address_v4(ip_addr_bytes).to_string(); + +    byte_copy(iface.read_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, subnet), 4), ip_addr_bytes); +    mb_eeprom["subnet"] = boost::asio::ip::address_v4(ip_addr_bytes).to_string(); + +    byte_copy(iface.read_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, gateway), 4), ip_addr_bytes); +    mb_eeprom["gateway"] = boost::asio::ip::address_v4(ip_addr_bytes).to_string(); + +    //gpsdo capabilities +    boost::uint8_t gpsdo_byte = iface.read_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, gpsdo), 1).at(0); +    switch(n200_gpsdo_type(gpsdo_byte)){ +    case N200_GPSDO_INTERNAL: mb_eeprom["gpsdo"] = "internal"; break; +    case N200_GPSDO_ONBOARD: mb_eeprom["gpsdo"] = "onboard"; break; +    default: mb_eeprom["gpsdo"] = "none"; +    } + +    //extract the serial +    mb_eeprom["serial"] = bytes_to_string(iface.read_eeprom( +        N100_EEPROM_ADDR, offsetof(n100_eeprom_map, serial), SERIAL_LEN +    )); + +    //extract the name +    mb_eeprom["name"] = bytes_to_string(iface.read_eeprom( +        N100_EEPROM_ADDR, offsetof(n100_eeprom_map, name), NAME_MAX_LEN +    )); + +    //Empty serial correction: use the mac address to determine serial. +    //Older usrp2 models don't have a serial burned into EEPROM. +    //The lower mac address bits will function as the serial number. +    if (mb_eeprom["serial"].empty()){ +        byte_vector_t mac_addr_bytes = mac_addr_t::from_string(mb_eeprom["mac-addr"]).to_bytes(); +        unsigned serial = mac_addr_bytes.at(5) | (unsigned(mac_addr_bytes.at(4) & 0x0f) << 8); +        mb_eeprom["serial"] = boost::lexical_cast<std::string>(serial); +    } +} + +static void store_n100(const mboard_eeprom_t &mb_eeprom, i2c_iface &iface){ +    //parse the revision number +    if (mb_eeprom.has_key("hardware")) iface.write_eeprom( +        N100_EEPROM_ADDR, offsetof(n100_eeprom_map, hardware), +        string_to_uint16_bytes(mb_eeprom["hardware"]) +    ); + +    //parse the revision number +    if (mb_eeprom.has_key("revision")) iface.write_eeprom( +        N100_EEPROM_ADDR, offsetof(n100_eeprom_map, revision), +        string_to_uint16_bytes(mb_eeprom["revision"]) +    ); + +    //parse the product code +    if (mb_eeprom.has_key("product")) iface.write_eeprom( +        N100_EEPROM_ADDR, offsetof(n100_eeprom_map, product), +        string_to_uint16_bytes(mb_eeprom["product"]) +    ); + +    //store the addresses +    if (mb_eeprom.has_key("mac-addr")) iface.write_eeprom( +        N100_EEPROM_ADDR, offsetof(n100_eeprom_map, mac_addr), +        mac_addr_t::from_string(mb_eeprom["mac-addr"]).to_bytes() +    ); + +    if (mb_eeprom.has_key("ip-addr")){ +        byte_vector_t ip_addr_bytes(4); +        byte_copy(boost::asio::ip::address_v4::from_string(mb_eeprom["ip-addr"]).to_bytes(), ip_addr_bytes); +        iface.write_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, ip_addr), ip_addr_bytes); +    } + +    if (mb_eeprom.has_key("subnet")){ +        byte_vector_t ip_addr_bytes(4); +        byte_copy(boost::asio::ip::address_v4::from_string(mb_eeprom["subnet"]).to_bytes(), ip_addr_bytes); +        iface.write_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, subnet), ip_addr_bytes); +    } + +    if (mb_eeprom.has_key("gateway")){ +        byte_vector_t ip_addr_bytes(4); +        byte_copy(boost::asio::ip::address_v4::from_string(mb_eeprom["gateway"]).to_bytes(), ip_addr_bytes); +        iface.write_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, gateway), ip_addr_bytes); +    } + +    //gpsdo capabilities +    if (mb_eeprom.has_key("gpsdo")){ +        boost::uint8_t gpsdo_byte = N200_GPSDO_NONE; +        if (mb_eeprom["gpsdo"] == "internal") gpsdo_byte = N200_GPSDO_INTERNAL; +        if (mb_eeprom["gpsdo"] == "onboard") gpsdo_byte = N200_GPSDO_ONBOARD; +        iface.write_eeprom(N100_EEPROM_ADDR, offsetof(n100_eeprom_map, gpsdo), byte_vector_t(1, gpsdo_byte)); +    } + +    //store the serial +    if (mb_eeprom.has_key("serial")) iface.write_eeprom( +        N100_EEPROM_ADDR, offsetof(n100_eeprom_map, serial), +        string_to_bytes(mb_eeprom["serial"], SERIAL_LEN) +    ); + +    //store the name +    if (mb_eeprom.has_key("name")) iface.write_eeprom( +        N100_EEPROM_ADDR, offsetof(n100_eeprom_map, name), +        string_to_bytes(mb_eeprom["name"], NAME_MAX_LEN) +    ); +} + +/*********************************************************************** + * Implementation of B000 load/store + **********************************************************************/ +static const boost::uint8_t B000_EEPROM_ADDR = 0x50; +static const size_t B000_SERIAL_LEN = 8; + +//use char array so we dont need to attribute packed +struct b000_eeprom_map{ +    unsigned char _r[221]; +    unsigned char mcr[4]; +    unsigned char name[NAME_MAX_LEN]; +    unsigned char serial[B000_SERIAL_LEN]; +}; + +static void load_b000(mboard_eeprom_t &mb_eeprom, i2c_iface &iface){ +    //extract the serial +    mb_eeprom["serial"] = bytes_to_string(iface.read_eeprom( +        B000_EEPROM_ADDR, offsetof(b000_eeprom_map, serial), B000_SERIAL_LEN +    )); + +    //extract the name +    mb_eeprom["name"] = bytes_to_string(iface.read_eeprom( +        B000_EEPROM_ADDR, offsetof(b000_eeprom_map, name), NAME_MAX_LEN +    )); + +    //extract master clock rate as a 32-bit uint in Hz +    boost::uint32_t master_clock_rate; +    const byte_vector_t rate_bytes = iface.read_eeprom( +        B000_EEPROM_ADDR, offsetof(b000_eeprom_map, mcr), sizeof(master_clock_rate) +    ); +    std::copy( +        rate_bytes.begin(), rate_bytes.end(), //input +        reinterpret_cast<boost::uint8_t *>(&master_clock_rate) //output +    ); +    master_clock_rate = ntohl(master_clock_rate); +    if (master_clock_rate > 1e6 and master_clock_rate < 1e9){ +        mb_eeprom["mcr"] = boost::lexical_cast<std::string>(master_clock_rate); +    } +    else mb_eeprom["mcr"] = ""; +} + +static void store_b000(const mboard_eeprom_t &mb_eeprom, i2c_iface &iface){ +    //store the serial +    if (mb_eeprom.has_key("serial")) iface.write_eeprom( +        B000_EEPROM_ADDR, offsetof(b000_eeprom_map, serial), +        string_to_bytes(mb_eeprom["serial"], B000_SERIAL_LEN) +    ); + +    //store the name +    if (mb_eeprom.has_key("name")) iface.write_eeprom( +        B000_EEPROM_ADDR, offsetof(b000_eeprom_map, name), +        string_to_bytes(mb_eeprom["name"], NAME_MAX_LEN) +    ); + +    //store the master clock rate as a 32-bit uint in Hz +    if (mb_eeprom.has_key("mcr")){ +        boost::uint32_t master_clock_rate = boost::uint32_t(boost::lexical_cast<double>(mb_eeprom["mcr"])); +        master_clock_rate = htonl(master_clock_rate); +        const byte_vector_t rate_bytes( +            reinterpret_cast<const boost::uint8_t *>(&master_clock_rate), +            reinterpret_cast<const boost::uint8_t *>(&master_clock_rate) + sizeof(master_clock_rate) +        ); +        iface.write_eeprom( +            B000_EEPROM_ADDR, offsetof(b000_eeprom_map, mcr), rate_bytes +        ); +    } +} + +/*********************************************************************** + * Implementation of B100 load/store + **********************************************************************/ +static const boost::uint8_t B100_EEPROM_ADDR = 0x50; + +//use char array so we dont need to attribute packed +struct b100_eeprom_map{ +    unsigned char _r[220]; +    unsigned char revision[2]; +    unsigned char product[2]; +    unsigned char name[NAME_MAX_LEN]; +    unsigned char serial[SERIAL_LEN]; +}; + +static void load_b100(mboard_eeprom_t &mb_eeprom, i2c_iface &iface){ +    //extract the revision number +    mb_eeprom["revision"] = uint16_bytes_to_string( +        iface.read_eeprom(B100_EEPROM_ADDR, offsetof(b100_eeprom_map, revision), 2) +    ); + +    //extract the product code +    mb_eeprom["product"] = uint16_bytes_to_string( +        iface.read_eeprom(B100_EEPROM_ADDR, offsetof(b100_eeprom_map, product), 2) +    ); + +    //extract the serial +    mb_eeprom["serial"] = bytes_to_string(iface.read_eeprom( +        B100_EEPROM_ADDR, offsetof(b100_eeprom_map, serial), SERIAL_LEN +    )); + +    //extract the name +    mb_eeprom["name"] = bytes_to_string(iface.read_eeprom( +        B100_EEPROM_ADDR, offsetof(b100_eeprom_map, name), NAME_MAX_LEN +    )); +} + +static void store_b100(const mboard_eeprom_t &mb_eeprom, i2c_iface &iface){ +    //parse the revision number +    if (mb_eeprom.has_key("revision")) iface.write_eeprom( +        B100_EEPROM_ADDR, offsetof(b100_eeprom_map, revision), +        string_to_uint16_bytes(mb_eeprom["revision"]) +    ); + +    //parse the product code +    if (mb_eeprom.has_key("product")) iface.write_eeprom( +        B100_EEPROM_ADDR, offsetof(b100_eeprom_map, product), +        string_to_uint16_bytes(mb_eeprom["product"]) +    ); + +    //store the serial +    if (mb_eeprom.has_key("serial")) iface.write_eeprom( +        B100_EEPROM_ADDR, offsetof(b100_eeprom_map, serial), +        string_to_bytes(mb_eeprom["serial"], SERIAL_LEN) +    ); + +    //store the name +    if (mb_eeprom.has_key("name")) iface.write_eeprom( +        B100_EEPROM_ADDR, offsetof(b100_eeprom_map, name), +        string_to_bytes(mb_eeprom["name"], NAME_MAX_LEN) +    ); +} + +/*********************************************************************** + * Implementation of E100 load/store + **********************************************************************/ +static const boost::uint8_t E100_EEPROM_ADDR = 0x51; + +struct e100_eeprom_map{ +    boost::uint16_t vendor; +    boost::uint16_t device; +    unsigned char revision; +    unsigned char content; +    unsigned char model[8]; +    unsigned char env_var[16]; +    unsigned char env_setting[64]; +    unsigned char serial[10]; +    unsigned char name[NAME_MAX_LEN]; +}; + +template <typename T> static const byte_vector_t to_bytes(const T &item){ +    return byte_vector_t( +        reinterpret_cast<const byte_vector_t::value_type *>(&item), +        reinterpret_cast<const byte_vector_t::value_type *>(&item)+sizeof(item) +    ); +} + +#define sizeof_member(struct_name, member_name) \ +    sizeof(reinterpret_cast<struct_name*>(NULL)->member_name) + +static void load_e100(mboard_eeprom_t &mb_eeprom, i2c_iface &iface){ +    const size_t num_bytes = offsetof(e100_eeprom_map, model); +    byte_vector_t map_bytes = iface.read_eeprom(E100_EEPROM_ADDR, 0, num_bytes); +    e100_eeprom_map map; std::memcpy(&map, &map_bytes[0], map_bytes.size()); + +    mb_eeprom["vendor"] = boost::lexical_cast<std::string>(uhd::ntohx(map.vendor)); +    mb_eeprom["device"] = boost::lexical_cast<std::string>(uhd::ntohx(map.device)); +    mb_eeprom["revision"] = boost::lexical_cast<std::string>(unsigned(map.revision)); +    mb_eeprom["content"] = boost::lexical_cast<std::string>(unsigned(map.content)); + +    #define load_e100_string_xx(key) mb_eeprom[#key] = bytes_to_string(iface.read_eeprom( \ +        E100_EEPROM_ADDR, offsetof(e100_eeprom_map, key), sizeof_member(e100_eeprom_map, key) \ +    )); + +    load_e100_string_xx(model); +    load_e100_string_xx(env_var); +    load_e100_string_xx(env_setting); +    load_e100_string_xx(serial); +    load_e100_string_xx(name); +} + +static void store_e100(const mboard_eeprom_t &mb_eeprom, i2c_iface &iface){ + +    if (mb_eeprom.has_key("vendor")) iface.write_eeprom( +        E100_EEPROM_ADDR, offsetof(e100_eeprom_map, vendor), +        to_bytes(uhd::htonx(boost::lexical_cast<boost::uint16_t>(mb_eeprom["vendor"]))) +    ); + +    if (mb_eeprom.has_key("device")) iface.write_eeprom( +        E100_EEPROM_ADDR, offsetof(e100_eeprom_map, device), +        to_bytes(uhd::htonx(boost::lexical_cast<boost::uint16_t>(mb_eeprom["device"]))) +    ); + +    if (mb_eeprom.has_key("revision")) iface.write_eeprom( +        E100_EEPROM_ADDR, offsetof(e100_eeprom_map, revision), +        byte_vector_t(1, boost::lexical_cast<unsigned>(mb_eeprom["revision"])) +    ); + +    if (mb_eeprom.has_key("content")) iface.write_eeprom( +        E100_EEPROM_ADDR, offsetof(e100_eeprom_map, content), +        byte_vector_t(1, boost::lexical_cast<unsigned>(mb_eeprom["content"])) +    ); + +    #define store_e100_string_xx(key) if (mb_eeprom.has_key(#key)) iface.write_eeprom( \ +        E100_EEPROM_ADDR, offsetof(e100_eeprom_map, key), \ +        string_to_bytes(mb_eeprom[#key], sizeof_member(e100_eeprom_map, key)) \ +    ); + +    store_e100_string_xx(model); +    store_e100_string_xx(env_var); +    store_e100_string_xx(env_setting); +    store_e100_string_xx(serial); +    store_e100_string_xx(name); +} + +/*********************************************************************** + * Implementation of mboard eeprom + **********************************************************************/ +mboard_eeprom_t::mboard_eeprom_t(void){ +    /* NOP */ +} + +mboard_eeprom_t::mboard_eeprom_t(i2c_iface &iface, const std::string &which){ +    if (which == "N100") load_n100(*this, iface); +    if (which == "B000") load_b000(*this, iface); +    if (which == "B100") load_b100(*this, iface); +    if (which == "E100") load_e100(*this, iface); +} + +void mboard_eeprom_t::commit(i2c_iface &iface, const std::string &which) const{ +    if (which == "N100") store_n100(*this, iface); +    if (which == "B000") store_b000(*this, iface); +    if (which == "B100") store_b100(*this, iface); +    if (which == "E100") store_e100(*this, iface); +} diff --git a/host/lib/usrp/multi_usrp.cpp b/host/lib/usrp/multi_usrp.cpp new file mode 100644 index 000000000..1267da89c --- /dev/null +++ b/host/lib/usrp/multi_usrp.cpp @@ -0,0 +1,914 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include <uhd/property_tree.hpp> +#include <uhd/usrp/multi_usrp.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/utils/gain_group.hpp> +#include <uhd/usrp/dboard_id.hpp> +#include <uhd/usrp/mboard_eeprom.hpp> +#include <uhd/usrp/dboard_eeprom.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/thread.hpp> +#include <boost/foreach.hpp> +#include <boost/format.hpp> +#include <cmath> + +using namespace uhd; +using namespace uhd::usrp; + +const std::string multi_usrp::ALL_GAINS = ""; + +/*********************************************************************** + * Helper methods + **********************************************************************/ +static void do_samp_rate_warning_message( +    double target_rate, +    double actual_rate, +    const std::string &xx +){ +    static const double max_allowed_error = 1.0; //Sps +    if (std::abs(target_rate - actual_rate) > max_allowed_error){ +        UHD_MSG(warning) << boost::format( +            "The hardware does not support the requested %s sample rate:\n" +            "Target sample rate: %f MSps\n" +            "Actual sample rate: %f MSps\n" +        ) % xx % (target_rate/1e6) % (actual_rate/1e6); +    } +} + +static void do_tune_freq_warning_message( +    const tune_request_t &tune_req, +    double actual_freq, +    const std::string &xx +){ +    //forget the warning when manual policy +    if (tune_req.dsp_freq_policy == tune_request_t::POLICY_MANUAL) return; +    if (tune_req.rf_freq_policy == tune_request_t::POLICY_MANUAL) return; + +    const double target_freq = tune_req.target_freq; +    static const double max_allowed_error = 1.0; //Hz +    if (std::abs(target_freq - actual_freq) > max_allowed_error){ +        UHD_MSG(warning) << boost::format( +            "The hardware does not support the requested %s frequency:\n" +            "Target frequency: %f MHz\n" +            "Actual frequency: %f MHz\n" +        ) % xx % (target_freq/1e6) % (actual_freq/1e6); +    } +} + +static meta_range_t make_overall_tune_range( +    const meta_range_t &fe_range, +    const meta_range_t &dsp_range, +    const double bw +){ +    meta_range_t range; +    BOOST_FOREACH(const range_t &sub_range, fe_range){ +        range.push_back(range_t( +            sub_range.start() + std::max(dsp_range.start(), -bw), +            sub_range.stop() + std::min(dsp_range.stop(), bw), +            dsp_range.step() +        )); +    } +    return range; +} + +/*********************************************************************** + * Gain helper functions + **********************************************************************/ +static double get_gain_value(property_tree::sptr subtree){ +    return subtree->access<double>("value").get(); +} + +static void set_gain_value(property_tree::sptr subtree, const double gain){ +    subtree->access<double>("value").set(gain); +} + +static meta_range_t get_gain_range(property_tree::sptr subtree){ +    return subtree->access<meta_range_t>("range").get(); +} + +static gain_fcns_t make_gain_fcns_from_subtree(property_tree::sptr subtree){ +    gain_fcns_t gain_fcns; +    gain_fcns.get_range = boost::bind(&get_gain_range, subtree); +    gain_fcns.get_value = boost::bind(&get_gain_value, subtree); +    gain_fcns.set_value = boost::bind(&set_gain_value, subtree, _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 dsp_subtree, +    property_tree::sptr rf_fe_subtree, +    const tune_request_t &tune_request +){ +    //------------------------------------------------------------------ +    //-- calculate the LO offset, only used with automatic policy +    //------------------------------------------------------------------ +    double lo_offset = 0.0; +    if (rf_fe_subtree->access<bool>("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 = dsp_subtree->access<double>("rate/value").get(); +        const double bw = rf_fe_subtree->access<double>("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; +        rf_fe_subtree->access<double>("freq/value").set(target_rf_freq); +        break; + +    case tune_request_t::POLICY_MANUAL: +        target_rf_freq = tune_request.rf_freq; +        rf_fe_subtree->access<double>("freq/value").set(target_rf_freq); +        break; + +    case tune_request_t::POLICY_NONE: break; //does not set +    } +    const double actual_rf_freq = rf_fe_subtree->access<double>("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: +        dsp_subtree->access<double>("freq/value").set(target_dsp_freq); +        break; + +    case tune_request_t::POLICY_MANUAL: +        target_dsp_freq = tune_request.dsp_freq; +        dsp_subtree->access<double>("freq/value").set(target_dsp_freq); +        break; + +    case tune_request_t::POLICY_NONE: break; //does not set +    } +    const double actual_dsp_freq = dsp_subtree->access<double>("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 dsp_subtree, +    property_tree::sptr rf_fe_subtree +){ +    //extract actual dsp and IF frequencies +    const double actual_rf_freq = rf_fe_subtree->access<double>("freq/value").get(); +    const double actual_dsp_freq = dsp_subtree->access<double>("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->get_tree(); +    } + +    device::sptr get_device(void){ +        return _dev; +    } + +    dict<std::string, std::string> get_usrp_rx_info(size_t chan){ +        mboard_chan_pair mcp = rx_chan_to_mcp(chan); +        dict<std::string, std::string> usrp_info; + +        mboard_eeprom_t mb_eeprom = _tree->access<mboard_eeprom_t>(mb_root(mcp.mboard) / "eeprom").get(); +        dboard_eeprom_t db_eeprom = _tree->access<dboard_eeprom_t>(rx_rf_fe_root(mcp.chan).branch_path().branch_path() / "rx_eeprom").get(); + +        usrp_info["mboard_id"] = _tree->access<std::string>(mb_root(mcp.mboard) / "name").get(); +        usrp_info["mboard_name"] = mb_eeprom["name"]; +        usrp_info["mboard_serial"] = mb_eeprom["serial"]; +        usrp_info["rx_id"] = db_eeprom.id.to_pp_string(); +        usrp_info["rx_subdev_name"] = _tree->access<std::string>(rx_rf_fe_root(mcp.chan) / "name").get(); +        usrp_info["rx_subdev_spec"] = _tree->access<subdev_spec_t>(mb_root(mcp.mboard) / "rx_subdev_spec").get().to_string(); +        usrp_info["rx_serial"] = db_eeprom.serial; +        usrp_info["rx_antenna"] =  _tree->access<std::string>(rx_rf_fe_root(mcp.chan) / "antenna" / "value").get(); + +        return usrp_info; +    } + +    dict<std::string, std::string> get_usrp_tx_info(size_t chan){ +        mboard_chan_pair mcp = tx_chan_to_mcp(chan); +        dict<std::string, std::string> usrp_info; + +        mboard_eeprom_t mb_eeprom = _tree->access<mboard_eeprom_t>(mb_root(mcp.mboard) / "eeprom").get(); +        dboard_eeprom_t db_eeprom = _tree->access<dboard_eeprom_t>(tx_rf_fe_root(mcp.chan).branch_path().branch_path() / "tx_eeprom").get(); + +        usrp_info["mboard_id"] = _tree->access<std::string>(mb_root(mcp.mboard) / "name").get(); +        usrp_info["mboard_name"] = mb_eeprom["name"]; +        usrp_info["mboard_serial"] = mb_eeprom["serial"]; +        usrp_info["tx_id"] = db_eeprom.id.to_pp_string(); +        usrp_info["tx_subdev_name"] = _tree->access<std::string>(tx_rf_fe_root(mcp.chan) / "name").get(); +        usrp_info["tx_subdev_spec"] = _tree->access<subdev_spec_t>(mb_root(mcp.mboard) / "tx_subdev_spec").get().to_string(); +        usrp_info["tx_serial"] = db_eeprom.serial; +        usrp_info["tx_antenna"] = _tree->access<std::string>(tx_rf_fe_root(mcp.chan) / "antenna" / "value").get(); + +        return usrp_info; +    } + +    /******************************************************************* +     * Mboard methods +     ******************************************************************/ +    void set_master_clock_rate(double rate, size_t mboard){ +        if (mboard != ALL_MBOARDS){ +            _tree->access<double>(mb_root(mboard) / "tick_rate").set(rate); +            return; +        } +        for (size_t m = 0; m < get_num_mboards(); m++){ +            set_master_clock_rate(rate, m); +        } +    } + +    double get_master_clock_rate(size_t mboard){ +        return _tree->access<double>(mb_root(mboard) / "tick_rate").get(); +    } + +    std::string get_pp_string(void){ +        std::string buff = str(boost::format( +            "%s USRP:\n" +            "  Device: %s\n" +        ) +            % ((get_num_mboards() > 1)? "Multi" : "Single") +            % (_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 +                % (_tree->access<std::string>(mb_root(m) / "name").get()) +            ); +        } + +        //----------- rx side of life ---------------------------------- +        for (size_t m = 0, chan = 0; m < get_num_mboards(); m++){ +            for (; chan < (m + 1)*get_rx_subdev_spec(m).size(); chan++){ +                buff += str(boost::format( +                    "  RX Channel: %u\n" +                    "    RX DSP: %s\n" +                    "    RX Dboard: %s\n" +                    "    RX Subdev: %s\n" +                ) % chan +                    % 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()) +                ); +            } +        } + +        //----------- tx side of life ---------------------------------- +        for (size_t m = 0, chan = 0; m < get_num_mboards(); m++){ +            for (; chan < (m + 1)*get_tx_subdev_spec(m).size(); chan++){ +                buff += str(boost::format( +                    "  TX Channel: %u\n" +                    "    TX DSP: %s\n" +                    "    TX Dboard: %s\n" +                    "    TX Subdev: %s\n" +                ) % chan +                    % 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()) +                ); +            } +        } + +        return buff; +    } + +    std::string get_mboard_name(size_t mboard){ +        return _tree->access<std::string>(mb_root(mboard) / "name").get(); +    } + +    time_spec_t get_time_now(size_t mboard = 0){ +        return _tree->access<time_spec_t>(mb_root(mboard) / "time/now").get(); +    } + +    time_spec_t get_time_last_pps(size_t mboard = 0){ +        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){ +            _tree->access<time_spec_t>(mb_root(mboard) / "time/now").set(time_spec); +            return; +        } +        for (size_t m = 0; m < get_num_mboards(); m++){ +            set_time_now(time_spec, m); +        } +    } + +    void set_time_next_pps(const time_spec_t &time_spec, size_t mboard){ +        if (mboard != ALL_MBOARDS){ +            _tree->access<time_spec_t>(mb_root(mboard) / "time/pps").set(time_spec); +            return; +        } +        for (size_t m = 0; m < get_num_mboards(); m++){ +            set_time_next_pps(time_spec, m); +        } +    } + +    void set_time_unknown_pps(const time_spec_t &time_spec){ +        UHD_MSG(status) << "    1) catch time transition at pps edge" << std::endl; +        time_spec_t time_start = get_time_now(); +        time_spec_t time_start_last_pps = get_time_last_pps(); +        while(true){ +            if (get_time_last_pps() != time_start_last_pps) break; +            if ((get_time_now() - time_start) > time_spec_t(1.1)){ +                throw uhd::runtime_error( +                    "Board 0 may not be getting a PPS signal!\n" +                    "No PPS detected within the time interval.\n" +                    "See the application notes for your device.\n" +                ); +            } +        } + +        UHD_MSG(status) << "    2) set times next pps (synchronously)" << std::endl; +        set_time_next_pps(time_spec, ALL_MBOARDS); +        boost::this_thread::sleep(boost::posix_time::seconds(1)); + +        //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 = 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" +                    "Board 0 time is %f seconds.\n" +                    "Board %d time is %f seconds.\n" +                ) % m % time_0.get_real_secs() % m % time_i.get_real_secs(); +            } +        } +    } + +    bool get_time_synchronized(void){ +        for (size_t m = 1; m < get_num_mboards(); m++){ +            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; +    } + +    void set_command_time(const time_spec_t &time_spec, size_t mboard){ +        if (mboard != ALL_MBOARDS){ +            if (not _tree->exists(mb_root(mboard) / "time/cmd")){ +                throw uhd::not_implemented_error("timed command feature not implemented on this hardware"); +            } +            _tree->access<time_spec_t>(mb_root(mboard) / "time/cmd").set(time_spec); +            return; +        } +        for (size_t m = 0; m < get_num_mboards(); m++){ +            set_command_time(time_spec, m); +        } +    } + +    void clear_command_time(size_t mboard){ +        if (mboard != ALL_MBOARDS){ +            _tree->access<time_spec_t>(mb_root(mboard) / "time/cmd").set(time_spec_t(0.0)); +            return; +        } +        for (size_t m = 0; m < get_num_mboards(); m++){ +            clear_command_time(m); +        } +    } + +    void issue_stream_cmd(const stream_cmd_t &stream_cmd, size_t chan){ +        if (chan != ALL_CHANS){ +            _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++){ +            issue_stream_cmd(stream_cmd, c); +        } +    } + +    void set_clock_config(const clock_config_t &clock_config, size_t mboard){ +        //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::REF_SMA: clock_source = "external"; break; +        case clock_config_t::REF_MIMO: clock_source = "mimo"; break; +        default: clock_source = "unknown"; +        } +        this->set_clock_source(clock_source, mboard); + +        //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"; +        } +        if (time_source == "external" and clock_config.pps_polarity == clock_config_t::PPS_NEG) time_source = "_external_"; +        this->set_time_source(time_source, mboard); +    } + +    void set_time_source(const std::string &source, const size_t mboard){ +        if (mboard != ALL_MBOARDS){ +            _tree->access<std::string>(mb_root(mboard) / "time_source" / "value").set(source); +            return; +        } +        for (size_t m = 0; m < get_num_mboards(); m++){ +            this->set_time_source(source, m); +        } +    } + +    std::string get_time_source(const size_t mboard){ +        return _tree->access<std::string>(mb_root(mboard) / "time_source" / "value").get(); +    } + +    std::vector<std::string> get_time_sources(const size_t mboard){ +        return _tree->access<std::vector<std::string> >(mb_root(mboard) / "time_source" / "options").get(); +    } + +    void set_clock_source(const std::string &source, const size_t mboard){ +        if (mboard != ALL_MBOARDS){ +            _tree->access<std::string>(mb_root(mboard) / "clock_source" / "value").set(source); +            return; +        } +        for (size_t m = 0; m < get_num_mboards(); m++){ +            this->set_clock_source(source, m); +        } +    } + +    std::string get_clock_source(const size_t mboard){ +        return _tree->access<std::string>(mb_root(mboard) / "clock_source" / "value").get(); +    } + +    std::vector<std::string> get_clock_sources(const size_t mboard){ +        return _tree->access<std::vector<std::string> >(mb_root(mboard) / "clock_source" / "options").get(); +    } + +    size_t get_num_mboards(void){ +        return _tree->list("/mboards").size(); +    } + +    sensor_value_t get_mboard_sensor(const std::string &name, size_t mboard){ +        return _tree->access<sensor_value_t>(mb_root(mboard) / "sensors" / name).get(); +    } + +    std::vector<std::string> get_mboard_sensor_names(size_t mboard){ +        return _tree->list(mb_root(mboard) / "sensors"); +    } + +    void set_user_register(const boost::uint8_t addr, const boost::uint32_t data, size_t mboard){ +        if (mboard != ALL_MBOARDS){ +            typedef std::pair<boost::uint8_t, boost::uint32_t> user_reg_t; +            _tree->access<user_reg_t>(mb_root(mboard) / "user/regs").set(user_reg_t(addr, data)); +            return; +        } +        for (size_t m = 0; m < get_num_mboards(); m++){ +            set_user_register(addr, data, m); +        } +    } + +    /******************************************************************* +     * RX methods +     ******************************************************************/ +    void set_rx_subdev_spec(const subdev_spec_t &spec, size_t mboard){ +        if (mboard != ALL_MBOARDS){ +            _tree->access<subdev_spec_t>(mb_root(mboard) / "rx_subdev_spec").set(spec); +            return; +        } +        for (size_t m = 0; m < get_num_mboards(); m++){ +            set_rx_subdev_spec(spec, m); +        } +    } + +    subdev_spec_t get_rx_subdev_spec(size_t mboard){ +        return _tree->access<subdev_spec_t>(mb_root(mboard) / "rx_subdev_spec").get(); +    } + +    size_t get_rx_num_channels(void){ +        size_t sum = 0; +        for (size_t m = 0; m < get_num_mboards(); m++){ +            sum += get_rx_subdev_spec(m).size(); +        } +        return sum; +    } + +    std::string get_rx_subdev_name(size_t chan){ +        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){ +            _tree->access<double>(rx_dsp_root(chan) / "rate" / "value").set(rate); +            do_samp_rate_warning_message(rate, get_rx_rate(chan), "RX"); +            return; +        } +        for (size_t c = 0; c < get_rx_num_channels(); c++){ +            set_rx_rate(rate, c); +        } +    } + +    double get_rx_rate(size_t chan){ +        return _tree->access<double>(rx_dsp_root(chan) / "rate" / "value").get(); +    } + +    meta_range_t get_rx_rates(size_t chan){ +        return _tree->access<meta_range_t>(rx_dsp_root(chan) / "rate" / "range").get(); +    } + +    tune_result_t set_rx_freq(const tune_request_t &tune_request, size_t chan){ +        tune_result_t r = tune_xx_subdev_and_dsp(RX_SIGN, _tree->subtree(rx_dsp_root(chan)), _tree->subtree(rx_rf_fe_root(chan)), tune_request); +        do_tune_freq_warning_message(tune_request, get_rx_freq(chan), "RX"); +        return r; +    } + +    double get_rx_freq(size_t chan){ +        return derive_freq_from_xx_subdev_and_dsp(RX_SIGN, _tree->subtree(rx_dsp_root(chan)), _tree->subtree(rx_rf_fe_root(chan))); +    } + +    freq_range_t get_rx_freq_range(size_t chan){ +        return make_overall_tune_range( +            _tree->access<meta_range_t>(rx_rf_fe_root(chan) / "freq" / "range").get(), +            _tree->access<meta_range_t>(rx_dsp_root(chan) / "freq" / "range").get(), +            this->get_rx_bandwidth(chan) +        ); +    } + +    freq_range_t get_fe_rx_freq_range(size_t chan){ +        return _tree->access<meta_range_t>(rx_rf_fe_root(chan) / "freq" / "range").get(); +    } + +    void set_rx_gain(double gain, const std::string &name, size_t chan){ +        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); +    } + +    gain_range_t get_rx_gain_range(const std::string &name, size_t chan){ +        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(); +    } + +    void set_rx_antenna(const std::string &ant, size_t chan){ +        _tree->access<std::string>(rx_rf_fe_root(chan) / "antenna" / "value").set(ant); +    } + +    std::string get_rx_antenna(size_t chan){ +        return _tree->access<std::string>(rx_rf_fe_root(chan) / "antenna" / "value").get(); +    } + +    std::vector<std::string> get_rx_antennas(size_t chan){ +        return _tree->access<std::vector<std::string> >(rx_rf_fe_root(chan) / "antenna" / "options").get(); +    } + +    void set_rx_bandwidth(double bandwidth, size_t chan){ +        _tree->access<double>(rx_rf_fe_root(chan) / "bandwidth" / "value").set(bandwidth); +    } + +    double get_rx_bandwidth(size_t chan){ +        return _tree->access<double>(rx_rf_fe_root(chan) / "bandwidth" / "value").get(); +    } + +    meta_range_t get_rx_bandwidth_range(size_t chan){ +        return _tree->access<meta_range_t>(rx_rf_fe_root(chan) / "bandwidth" / "range").get(); +    } + +    dboard_iface::sptr get_rx_dboard_iface(size_t chan){ +        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 _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 _tree->list(rx_rf_fe_root(chan) / "sensors"); +    } + +    void set_rx_dc_offset(const bool enb, size_t chan){ +        if (chan != ALL_CHANS){ +            _tree->access<bool>(rx_fe_root(chan) / "dc_offset" / "enable").set(enb); +            return; +        } +        for (size_t c = 0; c < get_rx_num_channels(); c++){ +            this->set_rx_dc_offset(enb, c); +        } +    } + +    void set_rx_dc_offset(const std::complex<double> &offset, size_t chan){ +        if (chan != ALL_CHANS){ +            _tree->access<std::complex<double> >(rx_fe_root(chan) / "dc_offset" / "value").set(offset); +            return; +        } +        for (size_t c = 0; c < get_rx_num_channels(); c++){ +            this->set_rx_dc_offset(offset, c); +        } +    } + +    void set_rx_iq_balance(const std::complex<double> &offset, size_t chan){ +        if (chan != ALL_CHANS){ +            _tree->access<std::complex<double> >(rx_fe_root(chan) / "iq_balance" / "value").set(offset); +            return; +        } +        for (size_t c = 0; c < get_rx_num_channels(); c++){ +            this->set_rx_iq_balance(offset, c); +        } +    } + +    /******************************************************************* +     * TX methods +     ******************************************************************/ +    void set_tx_subdev_spec(const subdev_spec_t &spec, size_t mboard){ +        if (mboard != ALL_MBOARDS){ +            _tree->access<subdev_spec_t>(mb_root(mboard) / "tx_subdev_spec").set(spec); +            return; +        } +        for (size_t m = 0; m < get_num_mboards(); m++){ +            set_tx_subdev_spec(spec, m); +        } +    } + +    subdev_spec_t get_tx_subdev_spec(size_t mboard){ +        return _tree->access<subdev_spec_t>(mb_root(mboard) / "tx_subdev_spec").get(); +    } + +    size_t get_tx_num_channels(void){ +        size_t sum = 0; +        for (size_t m = 0; m < get_num_mboards(); m++){ +            sum += get_tx_subdev_spec(m).size(); +        } +        return sum; +    } + +    std::string get_tx_subdev_name(size_t chan){ +        return _tree->access<std::string>(tx_rf_fe_root(chan) / "name").get(); +    } + +    void set_tx_rate(double rate, size_t chan){ +        if (chan != ALL_CHANS){ +            _tree->access<double>(tx_dsp_root(chan) / "rate" / "value").set(rate); +            do_samp_rate_warning_message(rate, get_tx_rate(chan), "TX"); +            return; +        } +        for (size_t c = 0; c < get_tx_num_channels(); c++){ +            set_tx_rate(rate, c); +        } +    } + +    double get_tx_rate(size_t chan){ +        return _tree->access<double>(tx_dsp_root(chan) / "rate" / "value").get(); +    } + +    meta_range_t get_tx_rates(size_t chan){ +        return _tree->access<meta_range_t>(tx_dsp_root(chan) / "rate" / "range").get(); +    } + +    tune_result_t set_tx_freq(const tune_request_t &tune_request, size_t chan){ +        tune_result_t r = tune_xx_subdev_and_dsp(TX_SIGN, _tree->subtree(tx_dsp_root(chan)), _tree->subtree(tx_rf_fe_root(chan)), tune_request); +        do_tune_freq_warning_message(tune_request, get_tx_freq(chan), "TX"); +        return r; +    } + +    double get_tx_freq(size_t chan){ +        return derive_freq_from_xx_subdev_and_dsp(TX_SIGN, _tree->subtree(tx_dsp_root(chan)), _tree->subtree(tx_rf_fe_root(chan))); +    } + +    freq_range_t get_tx_freq_range(size_t chan){ +        return make_overall_tune_range( +            _tree->access<meta_range_t>(tx_rf_fe_root(chan) / "freq" / "range").get(), +            _tree->access<meta_range_t>(tx_dsp_root(chan) / "freq" / "range").get(), +            this->get_tx_bandwidth(chan) +        ); +    } + +    freq_range_t get_fe_tx_freq_range(size_t chan){ +        return _tree->access<meta_range_t>(tx_rf_fe_root(chan) / "freq" / "range").get(); +    } + +    void set_tx_gain(double gain, const std::string &name, size_t chan){ +        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); +    } + +    gain_range_t get_tx_gain_range(const std::string &name, size_t chan){ +        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(); +    } + +    void set_tx_antenna(const std::string &ant, size_t chan){ +        _tree->access<std::string>(tx_rf_fe_root(chan) / "antenna" / "value").set(ant); +    } + +    std::string get_tx_antenna(size_t chan){ +        return _tree->access<std::string>(tx_rf_fe_root(chan) / "antenna" / "value").get(); +    } + +    std::vector<std::string> get_tx_antennas(size_t chan){ +        return _tree->access<std::vector<std::string> >(tx_rf_fe_root(chan) / "antenna" / "options").get(); +    } + +    void set_tx_bandwidth(double bandwidth, size_t chan){ +        _tree->access<double>(tx_rf_fe_root(chan) / "bandwidth" / "value").set(bandwidth); +    } + +    double get_tx_bandwidth(size_t chan){ +        return _tree->access<double>(tx_rf_fe_root(chan) / "bandwidth" / "value").get(); +    } + +    meta_range_t get_tx_bandwidth_range(size_t chan){ +        return _tree->access<meta_range_t>(tx_rf_fe_root(chan) / "bandwidth" / "range").get(); +    } + +    dboard_iface::sptr get_tx_dboard_iface(size_t chan){ +        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 _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 _tree->list(tx_rf_fe_root(chan) / "sensors"); +    } + +    void set_tx_dc_offset(const std::complex<double> &offset, size_t chan){ +        if (chan != ALL_CHANS){ +            _tree->access<std::complex<double> >(tx_fe_root(chan) / "dc_offset" / "value").set(offset); +            return; +        } +        for (size_t c = 0; c < get_tx_num_channels(); c++){ +            this->set_tx_dc_offset(offset, c); +        } +    } + +    void set_tx_iq_balance(const std::complex<double> &offset, size_t chan){ +        if (chan != ALL_CHANS){ +            _tree->access<std::complex<double> >(tx_fe_root(chan) / "iq_balance" / "value").set(offset); +            return; +        } +        for (size_t c = 0; c < get_tx_num_channels(); c++){ +            this->set_tx_iq_balance(offset, c); +        } +    } + +private: +    device::sptr _dev; +    property_tree::sptr _tree; + +    struct mboard_chan_pair{ +        size_t mboard, chan; +        mboard_chan_pair(void): mboard(0), chan(0){} +    }; + +    mboard_chan_pair rx_chan_to_mcp(size_t chan){ +        mboard_chan_pair mcp; +        mcp.chan = chan; +        for (mcp.mboard = 0; mcp.mboard < get_num_mboards(); mcp.mboard++){ +            size_t sss = get_rx_subdev_spec(mcp.mboard).size(); +            if (mcp.chan < sss) break; +            mcp.chan -= sss; +        } +        return mcp; +    } + +    mboard_chan_pair tx_chan_to_mcp(size_t chan){ +        mboard_chan_pair mcp; +        mcp.chan = chan; +        for (mcp.mboard = 0; mcp.mboard < get_num_mboards(); mcp.mboard++){ +            size_t sss = get_tx_subdev_spec(mcp.mboard).size(); +            if (mcp.chan < sss) break; +            mcp.chan -= sss; +        } +        return mcp; +    } + +    fs_path mb_root(const size_t mboard){ +        const std::string name = _tree->list("/mboards").at(mboard); +        return "/mboards/" + name; +    } + +    fs_path rx_dsp_root(const size_t chan){ +        mboard_chan_pair mcp = rx_chan_to_mcp(chan); +        const std::string name = _tree->list(mb_root(mcp.mboard) / "rx_dsps").at(mcp.chan); +        return mb_root(mcp.mboard) / "rx_dsps" / name; +    } + +    fs_path tx_dsp_root(const size_t chan){ +        mboard_chan_pair mcp = tx_chan_to_mcp(chan); +        const std::string name = _tree->list(mb_root(mcp.mboard) / "tx_dsps").at(mcp.chan); +        return mb_root(mcp.mboard) / "tx_dsps" / name; +    } + +    fs_path rx_fe_root(const size_t chan){ +        mboard_chan_pair mcp = rx_chan_to_mcp(chan); +        const subdev_spec_pair_t spec = get_rx_subdev_spec(mcp.mboard).at(mcp.chan); +        return mb_root(mcp.mboard) / "rx_frontends" / spec.db_name; +    } + +    fs_path tx_fe_root(const size_t chan){ +        mboard_chan_pair mcp = tx_chan_to_mcp(chan); +        const subdev_spec_pair_t spec = get_tx_subdev_spec(mcp.mboard).at(mcp.chan); +        return mb_root(mcp.mboard) / "tx_frontends" / spec.db_name; +    } + +    fs_path rx_rf_fe_root(const size_t chan){ +        mboard_chan_pair mcp = rx_chan_to_mcp(chan); +        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; +    } + +    fs_path tx_rf_fe_root(const size_t chan){ +        mboard_chan_pair mcp = tx_chan_to_mcp(chan); +        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){ +        mboard_chan_pair mcp = rx_chan_to_mcp(chan); +        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_subtree(_tree->subtree(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_subtree(_tree->subtree(rx_rf_fe_root(chan) / "gains" / name)), 1 /* high prio */); +        } +        return gg; +    } + +    gain_group::sptr tx_gain_group(size_t chan){ +        mboard_chan_pair mcp = tx_chan_to_mcp(chan); +        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_subtree(_tree->subtree(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_subtree(_tree->subtree(tx_rf_fe_root(chan) / "gains" / name)), 0 /* low prio */); +        } +        return gg; +    } +}; + +/*********************************************************************** + * The Make Function + **********************************************************************/ +multi_usrp::sptr multi_usrp::make(const device_addr_t &dev_addr){ +    return sptr(new multi_usrp_impl(dev_addr)); +} diff --git a/host/lib/usrp/subdev_spec.cpp b/host/lib/usrp/subdev_spec.cpp new file mode 100644 index 000000000..6912afec8 --- /dev/null +++ b/host/lib/usrp/subdev_spec.cpp @@ -0,0 +1,80 @@ +// +// 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/subdev_spec.hpp> +#include <uhd/exception.hpp> +#include <boost/algorithm/string.hpp> //for split +#include <boost/tokenizer.hpp> +#include <boost/format.hpp> +#include <boost/foreach.hpp> +#include <sstream> +#include <vector> + +using namespace uhd; +using namespace uhd::usrp; + +#define pair_tokenizer(inp) \ +    boost::tokenizer<boost::char_separator<char> > \ +    (inp, boost::char_separator<char>(" ")) + +subdev_spec_pair_t::subdev_spec_pair_t( +    const std::string &db_name, const std::string &sd_name +): +    db_name(db_name), +    sd_name(sd_name) +{ +    /* NOP */ +} + +bool usrp::operator==(const subdev_spec_pair_t &lhs, const subdev_spec_pair_t &rhs){ +    return (lhs.db_name == rhs.db_name) and (lhs.sd_name == rhs.sd_name); +} + +subdev_spec_t::subdev_spec_t(const std::string &markup){ +    BOOST_FOREACH(const std::string &pair, pair_tokenizer(markup)){ +        if (pair.empty()) continue; +        std::vector<std::string> db_sd; boost::split(db_sd, pair, boost::is_any_of(":")); +        switch(db_sd.size()){ +        case 1: this->push_back(subdev_spec_pair_t("", db_sd.front())); break; +        case 2: this->push_back(subdev_spec_pair_t(db_sd.front(), db_sd.back())); break; +        default: throw uhd::value_error("invalid subdev-spec markup string: "+markup); +        } +    } +} + +std::string subdev_spec_t::to_pp_string(void) const{ +    if (this->size() == 0) return "Empty Subdevice Specification"; + +    std::stringstream ss; +    size_t count = 0; +    ss << "Subdevice Specification:" << std::endl; +    BOOST_FOREACH(const subdev_spec_pair_t &pair, *this){ +        ss << boost::format( +            "    Channel %d: Daughterboard %s, Subdevice %s" +        ) % (count++) % pair.db_name % pair.sd_name << std::endl; +    } +    return ss.str(); +} + +std::string subdev_spec_t::to_string(void) const{ +    std::string markup; +    size_t count = 0; +    BOOST_FOREACH(const subdev_spec_pair_t &pair, *this){ +        markup += ((count++)? " " : "") + pair.db_name + ":" + pair.sd_name; +    } +    return markup; +} diff --git a/host/lib/usrp/usrp1/CMakeLists.txt b/host/lib/usrp/usrp1/CMakeLists.txt new file mode 100644 index 000000000..70bebe502 --- /dev/null +++ b/host/lib/usrp/usrp1/CMakeLists.txt @@ -0,0 +1,36 @@ +# +# 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/>. +# + +######################################################################## +# This file included, use CMake directory variables +######################################################################## + +######################################################################## +# Conditionally configure the USRP1 support +######################################################################## +LIBUHD_REGISTER_COMPONENT("USRP1" ENABLE_USRP1 ON "ENABLE_LIBUHD;ENABLE_USB" OFF) + +IF(ENABLE_USRP1) +    LIBUHD_APPEND_SOURCES( +        ${CMAKE_CURRENT_SOURCE_DIR}/codec_ctrl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/dboard_iface.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/io_impl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/soft_time_ctrl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/usrp1_iface.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/usrp1_impl.cpp +    ) +ENDIF(ENABLE_USRP1) diff --git a/host/lib/usrp/usrp1/codec_ctrl.cpp b/host/lib/usrp/usrp1/codec_ctrl.cpp new file mode 100644 index 000000000..7383c9833 --- /dev/null +++ b/host/lib/usrp/usrp1/codec_ctrl.cpp @@ -0,0 +1,426 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "codec_ctrl.hpp" +#include "ad9862_regs.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/utils/safe_call.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/algorithm.hpp> +#include <uhd/utils/byteswap.hpp> +#include <boost/cstdint.hpp> +#include <boost/format.hpp> +#include <boost/tuple/tuple.hpp> +#include <boost/math/special_functions/round.hpp> +#include <boost/math/special_functions/sign.hpp> +#include <boost/assign/list_of.hpp> +#include <iomanip> + +using namespace uhd; + +const gain_range_t usrp1_codec_ctrl::tx_pga_gain_range(-20, 0, double(0.1)); +const gain_range_t usrp1_codec_ctrl::rx_pga_gain_range(0, 20, 1); + +/*********************************************************************** + * Codec Control Implementation + **********************************************************************/ +class usrp1_codec_ctrl_impl : public usrp1_codec_ctrl { +public: +    //structors +    usrp1_codec_ctrl_impl(spi_iface::sptr iface, int spi_slave); +    ~usrp1_codec_ctrl_impl(void); + +    //aux adc and dac control +    double read_aux_adc(aux_adc_t which); +    void write_aux_dac(aux_dac_t which, double volts); + +    //duc control +    void set_duc_freq(double freq, double); +    void enable_tx_digital(bool enb); + +    //pga gain control +    void set_tx_pga_gain(double); +    double get_tx_pga_gain(void); +    void set_rx_pga_gain(double, char); +    double get_rx_pga_gain(char); +     +    //rx adc buffer control +    void bypass_adc_buffers(bool bypass); + +private: +    spi_iface::sptr _iface; +    int _spi_slave; +    ad9862_regs_t _ad9862_regs; +    void send_reg(boost::uint8_t addr); +    void recv_reg(boost::uint8_t addr); + +    double coarse_tune(double codec_rate, double freq); +    double fine_tune(double codec_rate, double freq); +}; + +/*********************************************************************** + * Codec Control Structors + **********************************************************************/ +usrp1_codec_ctrl_impl::usrp1_codec_ctrl_impl(spi_iface::sptr iface, int spi_slave){ +    _iface = iface; +    _spi_slave = spi_slave; + +    //soft reset +    _ad9862_regs.soft_reset = 1; +    this->send_reg(0); + +    //initialize the codec register settings +    _ad9862_regs.sdio_bidir = ad9862_regs_t::SDIO_BIDIR_SDIO_SDO; +    _ad9862_regs.lsb_first = ad9862_regs_t::LSB_FIRST_MSB; +    _ad9862_regs.soft_reset = 0; + +    //setup rx side of codec +    _ad9862_regs.byp_buffer_a = 1; +    _ad9862_regs.byp_buffer_b = 1; +    _ad9862_regs.buffer_a_pd = 1; +    _ad9862_regs.buffer_b_pd = 1; +    _ad9862_regs.rx_pga_a = 0; +    _ad9862_regs.rx_pga_b = 0; +    _ad9862_regs.rx_twos_comp = 1; +    _ad9862_regs.rx_hilbert = ad9862_regs_t::RX_HILBERT_DIS; + +    //setup tx side of codec +    _ad9862_regs.two_data_paths = ad9862_regs_t::TWO_DATA_PATHS_BOTH; +    _ad9862_regs.interleaved = ad9862_regs_t::INTERLEAVED_INTERLEAVED; +    _ad9862_regs.tx_pga_gain = 199; +    _ad9862_regs.tx_hilbert = ad9862_regs_t::TX_HILBERT_DIS; +    _ad9862_regs.interp = ad9862_regs_t::INTERP_4; +    _ad9862_regs.tx_twos_comp = 1; +    _ad9862_regs.fine_mode = ad9862_regs_t::FINE_MODE_NCO; +    _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_BYPASS; +    _ad9862_regs.dac_a_coarse_gain = 0x3; +    _ad9862_regs.dac_b_coarse_gain = 0x3; + +    //setup the dll +    _ad9862_regs.input_clk_ctrl = ad9862_regs_t::INPUT_CLK_CTRL_EXTERNAL; +    _ad9862_regs.dll_mult = ad9862_regs_t::DLL_MULT_2; +    _ad9862_regs.dll_mode = ad9862_regs_t::DLL_MODE_FAST; + +    //setup clockout +    _ad9862_regs.clkout2_div_factor = ad9862_regs_t::CLKOUT2_DIV_FACTOR_2; + +    //write the register settings to the codec +    for (boost::uint8_t addr = 0; addr <= 25; addr++) { +        this->send_reg(addr); +    } + +    //always start conversions for aux ADC +    _ad9862_regs.start_a = 1; +    _ad9862_regs.start_b = 1; + +    //aux adc clock +    _ad9862_regs.clk_4 = ad9862_regs_t::CLK_4_1_4; +    this->send_reg(34); +} + +usrp1_codec_ctrl_impl::~usrp1_codec_ctrl_impl(void){UHD_SAFE_CALL( +    //set aux dacs to zero +    this->write_aux_dac(AUX_DAC_A, 0); +    this->write_aux_dac(AUX_DAC_B, 0); +    this->write_aux_dac(AUX_DAC_C, 0); +    this->write_aux_dac(AUX_DAC_D, 0); + +    //power down +    _ad9862_regs.all_rx_pd = 1; +    this->send_reg(1); +    _ad9862_regs.tx_digital_pd = 1; +    _ad9862_regs.tx_analog_pd = ad9862_regs_t::TX_ANALOG_PD_BOTH; +    this->send_reg(8); +)} + +/*********************************************************************** + * Codec Control Gain Control Methods + **********************************************************************/ +static const int mtpgw = 255; //maximum tx pga gain word + +void usrp1_codec_ctrl_impl::set_tx_pga_gain(double gain){ +    int gain_word = int(mtpgw*(gain - tx_pga_gain_range.start())/(tx_pga_gain_range.stop() - tx_pga_gain_range.start())); +    _ad9862_regs.tx_pga_gain = uhd::clip(gain_word, 0, mtpgw); +    this->send_reg(16); +} + +double usrp1_codec_ctrl_impl::get_tx_pga_gain(void){ +    return (_ad9862_regs.tx_pga_gain*(tx_pga_gain_range.stop() - tx_pga_gain_range.start())/mtpgw) + tx_pga_gain_range.start(); +} + +static const int mrpgw = 0x14; //maximum rx pga gain word + +void usrp1_codec_ctrl_impl::set_rx_pga_gain(double gain, char which){ +    int gain_word = int(mrpgw*(gain - rx_pga_gain_range.start())/(rx_pga_gain_range.stop() - rx_pga_gain_range.start())); +    gain_word = uhd::clip(gain_word, 0, mrpgw); +    switch(which){ +    case 'A': +        _ad9862_regs.rx_pga_a = gain_word; +        this->send_reg(2); +        return; +    case 'B': +        _ad9862_regs.rx_pga_b = gain_word; +        this->send_reg(3); +        return; +    default: UHD_THROW_INVALID_CODE_PATH(); +    } +} + +double usrp1_codec_ctrl_impl::get_rx_pga_gain(char which){ +    int gain_word; +    switch(which){ +    case 'A': gain_word = _ad9862_regs.rx_pga_a; break; +    case 'B': gain_word = _ad9862_regs.rx_pga_b; break; +    default: UHD_THROW_INVALID_CODE_PATH(); +    } +    return (gain_word*(rx_pga_gain_range.stop() - rx_pga_gain_range.start())/mrpgw) + rx_pga_gain_range.start(); +} + +/*********************************************************************** + * Codec Control AUX ADC Methods + **********************************************************************/ +static double aux_adc_to_volts(boost::uint8_t high, boost::uint8_t low) +{ +    return double(((boost::uint16_t(high) << 2) | low)*3.3)/0x3ff; +} + +double usrp1_codec_ctrl_impl::read_aux_adc(aux_adc_t which){ +    switch(which){ +    case AUX_ADC_A1: +        _ad9862_regs.select_a = ad9862_regs_t::SELECT_A_AUX_ADC1; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(28); //read the value (2 bytes, 2 reads) +        this->recv_reg(29); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_a1_9_2, _ad9862_regs.aux_adc_a1_1_0); + +    case AUX_ADC_A2: +        _ad9862_regs.select_a = ad9862_regs_t::SELECT_A_AUX_ADC2; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(26); //read the value (2 bytes, 2 reads) +        this->recv_reg(27); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_a2_9_2, _ad9862_regs.aux_adc_a2_1_0); + +    case AUX_ADC_B1: +        _ad9862_regs.select_b = ad9862_regs_t::SELECT_B_AUX_ADC1; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(32); //read the value (2 bytes, 2 reads) +        this->recv_reg(33); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_b1_9_2, _ad9862_regs.aux_adc_b1_1_0); + +    case AUX_ADC_B2: +        _ad9862_regs.select_b = ad9862_regs_t::SELECT_B_AUX_ADC2; +        this->send_reg(34); //start conversion and select mux +        this->recv_reg(30); //read the value (2 bytes, 2 reads) +        this->recv_reg(31); +        return aux_adc_to_volts(_ad9862_regs.aux_adc_b2_9_2, _ad9862_regs.aux_adc_b2_1_0); +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +/*********************************************************************** + * Codec Control AUX DAC Methods + **********************************************************************/ +void usrp1_codec_ctrl_impl::write_aux_dac(aux_dac_t which, double volts) +{ +    //special case for aux dac d (aka sigma delta word) +    if (which == AUX_DAC_D) { +        boost::uint16_t dac_word = uhd::clip(boost::math::iround(volts*0xfff/3.3), 0, 0xfff); +        _ad9862_regs.sig_delt_11_4 = boost::uint8_t(dac_word >> 4); +        _ad9862_regs.sig_delt_3_0 = boost::uint8_t(dac_word & 0xf); +        this->send_reg(42); +        this->send_reg(43); +        return; +    } + +    //calculate the dac word for aux dac a, b, c +    boost::uint8_t dac_word = uhd::clip(boost::math::iround(volts*0xff/3.3), 0, 0xff); + +    //setup a lookup table for the aux dac params (reg ref, reg addr) +    typedef boost::tuple<boost::uint8_t*, boost::uint8_t> dac_params_t; +    uhd::dict<aux_dac_t, dac_params_t> aux_dac_to_params = boost::assign::map_list_of +        (AUX_DAC_A, dac_params_t(&_ad9862_regs.aux_dac_a, 36)) +        (AUX_DAC_B, dac_params_t(&_ad9862_regs.aux_dac_b, 37)) +        (AUX_DAC_C, dac_params_t(&_ad9862_regs.aux_dac_c, 38)) +    ; + +    //set the aux dac register +    UHD_ASSERT_THROW(aux_dac_to_params.has_key(which)); +    boost::uint8_t *reg_ref, reg_addr; +    boost::tie(reg_ref, reg_addr) = aux_dac_to_params[which]; +    *reg_ref = dac_word; +    this->send_reg(reg_addr); +} + +/*********************************************************************** + * Codec Control SPI Methods + **********************************************************************/ +void usrp1_codec_ctrl_impl::send_reg(boost::uint8_t addr) +{ +    boost::uint32_t reg = _ad9862_regs.get_write_reg(addr); + +    UHD_LOGV(often) +        << "codec control write reg: 0x" +        << std::setw(8) << std::hex << reg << std::endl +    ; +    _iface->write_spi(_spi_slave, +                         spi_config_t::EDGE_RISE, reg, 16); +} + +void usrp1_codec_ctrl_impl::recv_reg(boost::uint8_t addr) +{ +    boost::uint32_t reg = _ad9862_regs.get_read_reg(addr); + +    UHD_LOGV(often) +        << "codec control read reg: 0x" +        << std::setw(8) << std::hex << reg << std::endl +    ; + +    boost::uint32_t ret = _iface->read_spi(_spi_slave, +                                        spi_config_t::EDGE_RISE, reg, 16); + +    UHD_LOGV(often) +        << "codec control read ret: 0x" +        << std::setw(8) << std::hex << ret << std::endl +    ; + +    _ad9862_regs.set_reg(addr, boost::uint16_t(ret)); +} + +/*********************************************************************** + * DUC tuning  + **********************************************************************/ +double usrp1_codec_ctrl_impl::coarse_tune(double codec_rate, double freq) +{ +    double coarse_freq; + +    double coarse_freq_1 = codec_rate / 8; +    double coarse_freq_2 = codec_rate / 4; +    double coarse_limit_1 = coarse_freq_1 / 2; +    double coarse_limit_2 = (coarse_freq_1 + coarse_freq_2) / 2; +    double max_freq = coarse_freq_2 + .09375 * codec_rate; +  +    if (freq < -max_freq) { +        return false; +    } +    else if (freq < -coarse_limit_2) { +        _ad9862_regs.neg_coarse_tune = ad9862_regs_t::NEG_COARSE_TUNE_NEG_SHIFT; +        _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_FDAC_4; +        coarse_freq = -coarse_freq_2; +    } +    else if (freq < -coarse_limit_1) { +        _ad9862_regs.neg_coarse_tune = ad9862_regs_t::NEG_COARSE_TUNE_NEG_SHIFT; +        _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_FDAC_8; +        coarse_freq = -coarse_freq_1; +    } +    else if (freq < coarse_limit_1) { +        _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_BYPASS; +        coarse_freq = 0;  +    } +    else if (freq < coarse_limit_2) { +        _ad9862_regs.neg_coarse_tune = ad9862_regs_t::NEG_COARSE_TUNE_POS_SHIFT; +        _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_FDAC_8; +        coarse_freq = coarse_freq_1; +    } +    else if (freq <= max_freq) { +        _ad9862_regs.neg_coarse_tune = ad9862_regs_t::NEG_COARSE_TUNE_POS_SHIFT; +        _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_FDAC_4; +        coarse_freq = coarse_freq_2; +    } +    else { +        return 0;  +    } + +    return coarse_freq; +} + +double usrp1_codec_ctrl_impl::fine_tune(double codec_rate, double target_freq) +{ +    static const double scale_factor = std::pow(2.0, 24); + +    boost::uint32_t freq_word = boost::uint32_t( +        boost::math::round(abs((target_freq / codec_rate) * scale_factor))); + +    double actual_freq = freq_word * codec_rate / scale_factor; + +    if (target_freq < 0) { +        _ad9862_regs.neg_fine_tune = ad9862_regs_t::NEG_FINE_TUNE_NEG_SHIFT; +        actual_freq = -actual_freq;  +    } +    else { +        _ad9862_regs.neg_fine_tune = ad9862_regs_t::NEG_FINE_TUNE_POS_SHIFT; +    }  + +    _ad9862_regs.fine_mode = ad9862_regs_t::FINE_MODE_NCO; +    _ad9862_regs.ftw_23_16 = (freq_word >> 16) & 0xff; +    _ad9862_regs.ftw_15_8  = (freq_word >>  8) & 0xff; +    _ad9862_regs.ftw_7_0   = (freq_word >>  0) & 0xff; + +    return actual_freq; +} + +void usrp1_codec_ctrl_impl::set_duc_freq(double freq, double rate) +{ +    double codec_rate = rate * 2; + +    //correct for outside of rate (wrap around) +    freq = std::fmod(freq, rate); +    if (std::abs(freq) > rate/2.0) +        freq -= boost::math::sign(freq)*rate; + +    double coarse_freq = coarse_tune(codec_rate, freq); +    double fine_freq = fine_tune(codec_rate / 4, freq - coarse_freq); + +    UHD_LOG +        << "ad9862 tuning result:" << std::endl +        << "   requested:   " << freq << std::endl +        << "   actual:      " << coarse_freq + fine_freq << std::endl +        << "   coarse freq: " << coarse_freq << std::endl +        << "   fine freq:   " << fine_freq << std::endl +        << "   codec rate:  " << codec_rate << std::endl +    ; + +    this->send_reg(20); +    this->send_reg(21); +    this->send_reg(22); +    this->send_reg(23); +} + +void usrp1_codec_ctrl_impl::enable_tx_digital(bool enb){ +    _ad9862_regs.tx_digital_pd = (enb)? 0 : 1; +    this->send_reg(8); +} + +/*********************************************************************** + * Codec Control ADC buffer bypass + * Disable this for AC-coupled daughterboards (TVRX) + * By default it is initialized TRUE. + **********************************************************************/ +void usrp1_codec_ctrl_impl::bypass_adc_buffers(bool bypass) { +    _ad9862_regs.byp_buffer_a = bypass; +    _ad9862_regs.byp_buffer_b = bypass; +    this->send_reg(2); +} + +/*********************************************************************** + * Codec Control Make + **********************************************************************/ +usrp1_codec_ctrl::sptr usrp1_codec_ctrl::make(spi_iface::sptr iface, +                                              int 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 new file mode 100644 index 000000000..70f4e0b61 --- /dev/null +++ b/host/lib/usrp/usrp1/codec_ctrl.hpp @@ -0,0 +1,99 @@ +// +// 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_CODEC_CTRL_HPP +#define INCLUDED_USRP1_CODEC_CTRL_HPP + +#include <uhd/types/serial.hpp> +#include <uhd/types/ranges.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> + +/*! + * The usrp1 codec control: + * - Init/power down codec. + * - Read aux adc, write aux dac. + */ +class usrp1_codec_ctrl : boost::noncopyable{ +public: +    typedef boost::shared_ptr<usrp1_codec_ctrl> sptr; + +    static const uhd::gain_range_t tx_pga_gain_range; +    static const uhd::gain_range_t rx_pga_gain_range; + +    /*! +     * Make a new clock control object. +     * \param iface the spi iface object +     * \param spi_slave which spi device +     */ +    static sptr make(uhd::spi_iface::sptr iface, int spi_slave); + +    //! aux adc identifier constants +    enum aux_adc_t{ +        AUX_ADC_A2 = 0xA2, +        AUX_ADC_A1 = 0xA1, +        AUX_ADC_B2 = 0xB2, +        AUX_ADC_B1 = 0xB1 +    }; + +    /*! +     * Read an auxiliary adc: +     * The internals remember which aux adc was read last. +     * Therefore, the aux adc switch is only changed as needed. +     * \param which which of the 4 adcs +     * \return a value in volts +     */ +    virtual double read_aux_adc(aux_adc_t which) = 0; + +    //! aux dac identifier constants +    enum aux_dac_t{ +        AUX_DAC_A = 0xA, +        AUX_DAC_B = 0xB, +        AUX_DAC_C = 0xC, +        AUX_DAC_D = 0xD +    }; + +    /*! +     * Write an auxiliary dac. +     * \param which which of the 4 dacs +     * \param volts the level in in volts +     */ +    virtual void write_aux_dac(aux_dac_t which, double volts) = 0; + +    //! Set the TX PGA gain +    virtual void set_tx_pga_gain(double gain) = 0; + +    //! Get the TX PGA gain +    virtual double get_tx_pga_gain(void) = 0; + +    //! Set the RX PGA gain ('A' or 'B') +    virtual void set_rx_pga_gain(double gain, char which) = 0; + +    //! Get the RX PGA gain ('A' or 'B') +    virtual double get_rx_pga_gain(char which) = 0; + +    //! Set the TX modulator frequency +    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; + +    //! Enable or disable ADC buffer bypass +    virtual void bypass_adc_buffers(bool bypass) = 0; +}; + +#endif /* INCLUDED_USRP1_CODEC_CTRL_HPP */ diff --git a/host/lib/usrp/usrp1/dboard_iface.cpp b/host/lib/usrp/usrp1/dboard_iface.cpp new file mode 100644 index 000000000..34bbe1893 --- /dev/null +++ b/host/lib/usrp/usrp1/dboard_iface.cpp @@ -0,0 +1,397 @@ +// +// 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_iface.hpp" +#include "usrp1_impl.hpp" +#include "fpga_regs_common.h" +#include "usrp_spi_defs.h" +#include "fpga_regs_standard.h" +#include "codec_ctrl.hpp" +#include <uhd/usrp/dboard_iface.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/utils/assert_has.hpp> +#include <boost/assign/list_of.hpp> +#include <iostream> + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +static const dboard_id_t tvrx_id(0x0040); + +class usrp1_dboard_iface : public dboard_iface { +public: + +    usrp1_dboard_iface(usrp1_iface::sptr iface, +                       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; +        _codec = codec; + +        _dbsrx_classic_div = 1; + +        //yes this is evil but it's necessary for TVRX to work on USRP1 +        if(_rx_dboard_id == tvrx_id) _codec->bypass_adc_buffers(false); +        //else _codec->bypass_adc_buffers(false); //don't think this is necessary +    } + +    ~usrp1_dboard_iface() +    { +        /* NOP */ +    } + +    special_props_t get_special_props() +    { +        special_props_t props; +        props.soft_clock_divider = true; +        props.mangle_i2c_addrs = (_dboard_slot == usrp1_impl::DBOARD_SLOT_B); +        return props; +    } + +    void write_aux_dac(unit_t, aux_dac_t, double); +    double read_aux_adc(unit_t, aux_adc_t); + +    void _set_pin_ctrl(unit_t, boost::uint16_t); +    void _set_atr_reg(unit_t, atr_reg_t, boost::uint16_t); +    void _set_gpio_ddr(unit_t, boost::uint16_t); +    void _set_gpio_out(unit_t, boost::uint16_t); +    void set_gpio_debug(unit_t, int); +    boost::uint16_t read_gpio(unit_t); + +    void write_i2c(boost::uint8_t, const byte_vector_t &); +    byte_vector_t read_i2c(boost::uint8_t, size_t); + +    void write_spi(unit_t unit, +                   const spi_config_t &config, +                   boost::uint32_t data, +                   size_t num_bits); + +    boost::uint32_t read_write_spi(unit_t unit, +                                   const spi_config_t &config, +                                   boost::uint32_t data, +                                   size_t num_bits); + +    void set_clock_rate(unit_t, double); +    std::vector<double> get_clock_rates(unit_t); +    double get_clock_rate(unit_t); +    void set_clock_enabled(unit_t, bool); +    double get_codec_rate(unit_t); + +private: +    usrp1_iface::sptr _iface; +    usrp1_codec_ctrl::sptr _codec; +    unsigned _dbsrx_classic_div; +    const usrp1_impl::dboard_slot_t _dboard_slot; +    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_codec_ctrl::sptr codec, +                                           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, codec, dboard_slot, master_clock_rate, rx_dboard_id +    )); +} + +/*********************************************************************** + * Clock Rates + **********************************************************************/ +static const dboard_id_t dbsrx_classic_id(0x0002); + +/* + * Daughterboard reference clock register + * + * Bit  7    - 1 turns on refclk, 0 allows IO use + * Bits 6:0  - Divider value + */ +void usrp1_dboard_iface::set_clock_rate(unit_t unit, double rate) +{ +    assert_has(this->get_clock_rates(unit), rate, "dboard clock rate"); + +    if (unit == UNIT_RX && _rx_dboard_id == dbsrx_classic_id){ +        _dbsrx_classic_div = size_t(_master_clock_rate/rate); +        switch(_dboard_slot){ +        case usrp1_impl::DBOARD_SLOT_A: +            _iface->poke32(FR_RX_A_REFCLK, (_dbsrx_classic_div & 0x7f) | 0x80); +            break; + +        case usrp1_impl::DBOARD_SLOT_B: +            _iface->poke32(FR_RX_B_REFCLK, (_dbsrx_classic_div & 0x7f) | 0x80); +            break; +        } +    } +} + +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(_master_clock_rate / div); +    } +    else{ +        rates.push_back(_master_clock_rate); +    } +    return rates; +} + +double usrp1_dboard_iface::get_clock_rate(unit_t unit) +{ +    if (unit == UNIT_RX && _rx_dboard_id == dbsrx_classic_id){ +        return _master_clock_rate/_dbsrx_classic_div; +    } +    return _master_clock_rate; +} + +void usrp1_dboard_iface::set_clock_enabled(unit_t, bool) +{ +    //TODO we can only enable for special case anyway... +} + +double usrp1_dboard_iface::get_codec_rate(unit_t){ +    return _master_clock_rate; +} + +/*********************************************************************** + * GPIO + **********************************************************************/ +void usrp1_dboard_iface::_set_pin_ctrl(unit_t unit, boost::uint16_t value) +{ +    switch(unit) { +    case UNIT_RX: +        if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +             _iface->poke32(FR_ATR_MASK_1, value); +        else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +             _iface->poke32(FR_ATR_MASK_3, value); +        break; +    case UNIT_TX: +        if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +            _iface->poke32(FR_ATR_MASK_0, value); +        else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +            _iface->poke32(FR_ATR_MASK_2, value); +        break; +    } +} + +void usrp1_dboard_iface::_set_gpio_ddr(unit_t unit, boost::uint16_t value) +{ +    switch(unit) { +    case UNIT_RX: +        if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +            _iface->poke32(FR_OE_1, 0xffff0000 | value); +        else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +            _iface->poke32(FR_OE_3, 0xffff0000 | value); +        break; +    case UNIT_TX: +        if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +            _iface->poke32(FR_OE_0, 0xffff0000 | value); +        else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +            _iface->poke32(FR_OE_2, 0xffff0000 | value); +        break; +    } +} + +void usrp1_dboard_iface::_set_gpio_out(unit_t unit, boost::uint16_t value) +{ +    switch(unit) { +    case UNIT_RX: +        if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +            _iface->poke32(FR_IO_1, 0xffff0000 | value); +        else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +            _iface->poke32(FR_IO_3, 0xffff0000 | value); +        break; +    case UNIT_TX: +        if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +            _iface->poke32(FR_IO_0, 0xffff0000 | value); +        else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +            _iface->poke32(FR_IO_2, 0xffff0000 | value); +        break; +    } +} + +void usrp1_dboard_iface::set_gpio_debug(unit_t, int) +{ +    /* NOP */ +} + +boost::uint16_t usrp1_dboard_iface::read_gpio(unit_t unit) +{ +    boost::uint32_t out_value; + +    if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +        out_value = _iface->peek32(1); +    else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +        out_value = _iface->peek32(2); +    else +        UHD_THROW_INVALID_CODE_PATH(); + +    switch(unit) { +    case UNIT_RX: +        return (boost::uint16_t)((out_value >> 16) & 0x0000ffff); +    case UNIT_TX: +        return (boost::uint16_t)((out_value >>  0) & 0x0000ffff); +    } +    UHD_ASSERT_THROW(false); +} + +void usrp1_dboard_iface::_set_atr_reg(unit_t unit, +                                     atr_reg_t atr, boost::uint16_t value) +{ +    // Ignore unsupported states +    if ((atr == ATR_REG_IDLE) || (atr == ATR_REG_TX_ONLY)) +        return; +    if(atr == ATR_REG_RX_ONLY) { +        switch(unit) { +        case UNIT_RX: +            if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +                _iface->poke32(FR_ATR_RXVAL_1, value); +            else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +                _iface->poke32(FR_ATR_RXVAL_3, value); +            break; +        case UNIT_TX: +            if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +                _iface->poke32(FR_ATR_RXVAL_0, value); +            else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +                _iface->poke32(FR_ATR_RXVAL_2, value); +            break; +        } +    } else if (atr == ATR_REG_FULL_DUPLEX) { +        switch(unit) { +        case UNIT_RX: +            if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +                _iface->poke32(FR_ATR_TXVAL_1, value); +            else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +                _iface->poke32(FR_ATR_TXVAL_3, value); +            break; +        case UNIT_TX: +            if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A) +                _iface->poke32(FR_ATR_TXVAL_0, value); +            else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B) +                _iface->poke32(FR_ATR_TXVAL_2, value); +            break; +        } +    } +} +/*********************************************************************** + * SPI + **********************************************************************/ +/*! + * Static function to convert a unit type to a spi slave device number. + * \param unit the dboard interface unit type enum + * \param slot the side (A or B) the dboard is attached + * \return the slave device number + */ +static boost::uint32_t unit_to_otw_spi_dev(dboard_iface::unit_t unit, +                                           usrp1_impl::dboard_slot_t slot) +{ +    switch(unit) { +    case dboard_iface::UNIT_TX: +        if (slot == usrp1_impl::DBOARD_SLOT_A) +            return SPI_ENABLE_TX_A; +        else if (slot == usrp1_impl::DBOARD_SLOT_B) +            return SPI_ENABLE_TX_B; +        else +            break; +    case dboard_iface::UNIT_RX: +        if (slot == usrp1_impl::DBOARD_SLOT_A) +            return SPI_ENABLE_RX_A; +        else if (slot == usrp1_impl::DBOARD_SLOT_B) +            return SPI_ENABLE_RX_B; +        else +            break; +    } +    UHD_THROW_INVALID_CODE_PATH(); +} + +void usrp1_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, _dboard_slot), +                         config, data, num_bits); +} + +boost::uint32_t usrp1_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, _dboard_slot), +                                config, data, num_bits); +} + +/*********************************************************************** + * I2C + **********************************************************************/ +void usrp1_dboard_iface::write_i2c(boost::uint8_t addr, +                                   const byte_vector_t &bytes) +{ +    return _iface->write_i2c(addr, bytes); +} + +byte_vector_t usrp1_dboard_iface::read_i2c(boost::uint8_t addr, +                                           size_t num_bytes) +{ +    return _iface->read_i2c(addr, num_bytes); +} + +/*********************************************************************** + * Aux DAX/ADC + **********************************************************************/ +void usrp1_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, usrp1_codec_ctrl::aux_dac_t> +        which_to_aux_dac = map_list_of +                                     (AUX_DAC_A, usrp1_codec_ctrl::AUX_DAC_A) +                                     (AUX_DAC_B, usrp1_codec_ctrl::AUX_DAC_B) +                                     (AUX_DAC_C, usrp1_codec_ctrl::AUX_DAC_C) +                                     (AUX_DAC_D, usrp1_codec_ctrl::AUX_DAC_D); + +    _codec->write_aux_dac(which_to_aux_dac[which], value); +} + +double usrp1_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, usrp1_codec_ctrl::aux_adc_t> > +        unit_to_which_to_aux_adc = map_list_of(UNIT_RX, map_list_of +                                    (AUX_ADC_A, usrp1_codec_ctrl::AUX_ADC_A1) +                                    (AUX_ADC_B, usrp1_codec_ctrl::AUX_ADC_B1)) +                                              (UNIT_TX, map_list_of +                                    (AUX_ADC_A, usrp1_codec_ctrl::AUX_ADC_A2) +                                    (AUX_ADC_B, usrp1_codec_ctrl::AUX_ADC_B2)); + +    return _codec->read_aux_adc(unit_to_which_to_aux_adc[unit][which]); +} diff --git a/host/lib/usrp/usrp1/io_impl.cpp b/host/lib/usrp/usrp1/io_impl.cpp new file mode 100644 index 000000000..1d8b9bd76 --- /dev/null +++ b/host/lib/usrp/usrp1/io_impl.cpp @@ -0,0 +1,693 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "validate_subdev_spec.hpp" +#define SRPH_DONT_CHECK_SEQUENCE +#include "../../transport/super_recv_packet_handler.hpp" +#define SSPH_DONT_PAD_TO_ONE +#include "../../transport/super_send_packet_handler.hpp" +#include "usrp1_calc_mux.hpp" +#include "fpga_regs_standard.h" +#include "fpga_regs_common.h" +#include "usrp_commands.h" +#include "usrp1_impl.hpp" +#include <uhd/utils/msg.hpp> +#include <uhd/utils/tasks.hpp> +#include <uhd/utils/safe_call.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/make_shared.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; + +static const size_t alignment_padding = 512; + +/*********************************************************************** + * Helper struct to associate an offset with a buffer + **********************************************************************/ +struct offset_send_buffer{ +    offset_send_buffer(void){ +        /* NOP */ +    } + +    offset_send_buffer(managed_send_buffer::sptr buff, size_t offset = 0): +        buff(buff), offset(offset) +    { +        /* NOP */ +    } + +    //member variables +    managed_send_buffer::sptr buff; +    size_t offset; /* in bytes */ +}; + +/*********************************************************************** + * Reusable managed send buffer to handle aligned commits + **********************************************************************/ +class offset_managed_send_buffer : public managed_send_buffer{ +public: +    typedef boost::function<void(offset_send_buffer&, offset_send_buffer&, size_t)> commit_cb_type; +    offset_managed_send_buffer(const commit_cb_type &commit_cb): +        _commit_cb(commit_cb) +    { +        /* NOP */ +    } + +    void release(void){ +        this->_commit_cb(_curr_buff, _next_buff, size()); +    } + +    sptr get_new( +        offset_send_buffer &curr_buff, +        offset_send_buffer &next_buff +    ){ +        _curr_buff = curr_buff; +        _next_buff = next_buff; +        return make(this, +            _curr_buff.buff->cast<char *>() + _curr_buff.offset, +            _curr_buff.buff->size()         - _curr_buff.offset +        ); +    } + +private: +    offset_send_buffer _curr_buff, _next_buff; +    commit_cb_type _commit_cb; +}; + +/*********************************************************************** + * BS VRT packer/unpacker functions (since samples don't have headers) + **********************************************************************/ +static void usrp1_bs_vrt_packer( +    boost::uint32_t *, +    vrt::if_packet_info_t &if_packet_info +){ +    if_packet_info.num_header_words32 = 0; +    if_packet_info.num_packet_words32 = if_packet_info.num_payload_words32; +} + +static void usrp1_bs_vrt_unpacker( +    const boost::uint32_t *, +    vrt::if_packet_info_t &if_packet_info +){ +    if_packet_info.packet_type = vrt::if_packet_info_t::PACKET_TYPE_DATA; +    if_packet_info.num_payload_words32 = if_packet_info.num_packet_words32; +    if_packet_info.num_payload_bytes = if_packet_info.num_packet_words32*sizeof(boost::uint32_t); +    if_packet_info.num_header_words32 = 0; +    if_packet_info.packet_count = 0; +    if_packet_info.sob = false; +    if_packet_info.eob = false; +    if_packet_info.has_sid = false; +    if_packet_info.has_cid = false; +    if_packet_info.has_tsi = false; +    if_packet_info.has_tsf = false; +    if_packet_info.has_tlr = false; +} + +/*********************************************************************** + * IO Implementation Details + **********************************************************************/ +struct usrp1_impl::io_impl{ +    io_impl(zero_copy_if::sptr data_transport): +        data_transport(data_transport), +        curr_buff(offset_send_buffer(data_transport->get_send_buff())), +        omsb(boost::bind(&usrp1_impl::io_impl::commit_send_buff, this, _1, _2, _3)) +    { +        /* NOP */ +    } + +    ~io_impl(void){ +        UHD_SAFE_CALL(flush_send_buff();) +    } + +    zero_copy_if::sptr data_transport; + +    //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 +    //since the vrt packet handler obeys this, we are ok +    offset_send_buffer curr_buff; +    offset_managed_send_buffer omsb; +    void commit_send_buff(offset_send_buffer&, offset_send_buffer&, size_t); +    void flush_send_buff(void); +    managed_send_buffer::sptr get_send_buff(double timeout){ +        //try to get a new managed buffer with timeout +        offset_send_buffer next_buff(data_transport->get_send_buff(timeout)); +        if (not next_buff.buff.get()) return managed_send_buffer::sptr(); /* propagate timeout here */ + +        //make a new managed buffer with the offset buffs +        return omsb.get_new(curr_buff, next_buff); +    } + +    task::sptr vandal_task; +    boost::system_time last_send_time; +}; + +/*! + * Perform an actual commit on the send buffer: + * Copy the remainder of alignment to the next buffer. + * Commit the current buffer at multiples of alignment. + */ +void usrp1_impl::io_impl::commit_send_buff( +    offset_send_buffer &curr, +    offset_send_buffer &next, +    size_t num_bytes +){ +    //total number of bytes now in the current buffer +    size_t bytes_in_curr_buffer = curr.offset + num_bytes; + +    //calculate how many to commit and remainder +    size_t num_bytes_remaining = bytes_in_curr_buffer % alignment_padding; +    size_t num_bytes_to_commit = bytes_in_curr_buffer - num_bytes_remaining; + +    //copy the remainder into the next buffer +    std::memcpy( +        next.buff->cast<char *>() + next.offset, +        curr.buff->cast<char *>() + num_bytes_to_commit, +        num_bytes_remaining +    ); + +    //update the offset into the next buffer +    next.offset += num_bytes_remaining; + +    //commit the current buffer +    curr.buff->commit(num_bytes_to_commit); + +    //store the next buffer for the next call +    curr_buff = next; +} + +/*! + * Flush the current buffer by padding out to alignment and committing. + */ +void usrp1_impl::io_impl::flush_send_buff(void){ +    //calculate the number of bytes to alignment +    size_t bytes_to_pad = (-1*curr_buff.offset)%alignment_padding; + +    //send at least alignment_padding to guarantee zeros are sent +    if (bytes_to_pad == 0) bytes_to_pad = alignment_padding; + +    //get the buffer, clear, and commit (really current buffer) +    managed_send_buffer::sptr buff = this->get_send_buff(.1); +    if (buff.get() != NULL){ +        std::memset(buff->cast<void *>(), 0, bytes_to_pad); +        buff->commit(bytes_to_pad); +    } +} + +/*********************************************************************** + * Initialize internals within this file + **********************************************************************/ +void usrp1_impl::io_init(void){ + +    _io_impl = UHD_PIMPL_MAKE(io_impl, (_data_transport)); + +    //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(); + +    //create a new vandal thread to poll xerflow conditions +    _io_impl->vandal_task = task::make(boost::bind( +        &usrp1_impl::vandal_conquest_loop, this +    )); +} + +void usrp1_impl::rx_stream_on_off(bool 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(void){ + +    //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; +    } +} + +/*********************************************************************** + * RX streamer wrapper that talks to soft time control + **********************************************************************/ +class usrp1_recv_packet_streamer : public sph::recv_packet_handler, public rx_streamer{ +public: +    usrp1_recv_packet_streamer(const size_t max_num_samps, soft_time_ctrl::sptr stc){ +        _max_num_samps = max_num_samps; +        _stc = stc; +    } + +    size_t get_num_channels(void) const{ +        return this->size(); +    } + +    size_t get_max_num_samps(void) const{ +        return _max_num_samps; +    } + +    size_t recv( +        const rx_streamer::buffs_type &buffs, +        const size_t nsamps_per_buff, +        uhd::rx_metadata_t &metadata, +        const double timeout, +        const bool one_packet +    ){ +        //interleave a "soft" inline message into the receive stream: +        if (_stc->get_inline_queue().pop_with_haste(metadata)) return 0; + +        size_t num_samps_recvd = sph::recv_packet_handler::recv( +            buffs, nsamps_per_buff, metadata, timeout, one_packet +        ); + +        return _stc->recv_post(metadata, num_samps_recvd); +    } + +private: +    size_t _max_num_samps; +    soft_time_ctrl::sptr _stc; +}; + +/*********************************************************************** + * TX streamer wrapper that talks to soft time control + **********************************************************************/ +class usrp1_send_packet_streamer : public sph::send_packet_handler, public tx_streamer{ +public: +    usrp1_send_packet_streamer(const size_t max_num_samps, soft_time_ctrl::sptr stc, boost::function<void(bool)> tx_enb_fcn){ +        _max_num_samps = max_num_samps; +        this->set_max_samples_per_packet(_max_num_samps); +        _stc = stc; +        _tx_enb_fcn = tx_enb_fcn; +    } + +    size_t get_num_channels(void) const{ +        return this->size(); +    } + +    size_t get_max_num_samps(void) const{ +        return _max_num_samps; +    } + +    size_t send( +        const tx_streamer::buffs_type &buffs, +        const size_t nsamps_per_buff, +        const uhd::tx_metadata_t &metadata, +        const double timeout_ +    ){ +        double timeout = timeout_; //rw copy +        _stc->send_pre(metadata, timeout); + +        _tx_enb_fcn(true); //always enable (it will do the right thing) +        size_t num_samps_sent = sph::send_packet_handler::send( +            buffs, nsamps_per_buff, metadata, timeout +        ); + +        //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){ +            async_metadata_t metadata; +            metadata.channel = 0; +            metadata.has_time_spec = true; +            metadata.time_spec = _stc->get_time(); +            metadata.event_code = async_metadata_t::EVENT_CODE_BURST_ACK; +            _stc->get_async_queue().push_with_pop_on_full(metadata); +            _tx_enb_fcn(false); +        } + +        return num_samps_sent; +    } + +private: +    size_t _max_num_samps; +    soft_time_ctrl::sptr _stc; +    boost::function<void(bool)> _tx_enb_fcn; +}; + +/*********************************************************************** + * Properties callback methods below + **********************************************************************/ +void usrp1_impl::update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){ + +    //sanity checking +    validate_subdev_spec(_tree, spec, "rx"); + +    _rx_subdev_spec = spec; //shadow + +    //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){ + +    //sanity checking +    validate_subdev_spec(_tree, spec, "tx"); + +    _tx_subdev_spec = spec; //shadow + +    //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); +} + +void usrp1_impl::update_tick_rate(const double rate){ +    //updating this variable should: +    //update dboard iface -> it has a reference +    //update dsp freq bounds -> publisher +    _master_clock_rate = rate; +} + +uhd::meta_range_t usrp1_impl::get_rx_dsp_host_rates(void){ +    meta_range_t range; +    const size_t div = this->has_rx_halfband()? 2 : 1; +    for (int rate = 256; rate >= 4; rate -= div){ +        range.push_back(range_t(_master_clock_rate/rate)); +    } +    return range; +} + +uhd::meta_range_t usrp1_impl::get_tx_dsp_host_rates(void){ +    meta_range_t range; +    const size_t div = this->has_tx_halfband()? 2 : 1; +    for (int rate = 256; rate >= 8; rate -= div){ +        range.push_back(range_t(_master_clock_rate/rate)); +    } +    return range; +} + +double usrp1_impl::update_rx_samp_rate(size_t dspno, const double samp_rate){ + +    const size_t div = this->has_rx_halfband()? 2 : 1; +    const size_t rate = boost::math::iround(_master_clock_rate/this->get_rx_dsp_host_rates().clip(samp_rate, true)); + +    if (rate < 8 and this->has_rx_halfband()) UHD_MSG(warning) << +        "USRP1 cannot achieve decimations below 8 when the half-band filter is present.\n" +        "The usrp1_fpga_4rx.rbf file is a special FPGA image without RX half-band filters.\n" +        "To load this image, set the device address key/value pair: fpga=usrp1_fpga_4rx.rbf\n" +    << std::endl; + +    if (dspno == 0){ //only care if dsp0 is set since its homogeneous +        bool s = this->disable_rx(); +        _iface->poke32(FR_RX_SAMPLE_RATE_DIV, div - 1); +        _iface->poke32(FR_DECIM_RATE, rate/div - 1); +        this->restore_rx(s); + +        //update the streamer if created +        boost::shared_ptr<usrp1_recv_packet_streamer> my_streamer = +            boost::dynamic_pointer_cast<usrp1_recv_packet_streamer>(_rx_streamer.lock()); +        if (my_streamer.get() != NULL){ +            my_streamer->set_samp_rate(_master_clock_rate / rate); +        } +    } + +    return _master_clock_rate / rate; +} + +double usrp1_impl::update_tx_samp_rate(size_t dspno, const double samp_rate){ + +    const size_t div = this->has_tx_halfband()? 4 : 2; //doubled for codec interp +    const size_t rate = boost::math::iround(_master_clock_rate/this->get_tx_dsp_host_rates().clip(samp_rate, true)); + +    if (dspno == 0){ //only care if dsp0 is set since its homogeneous +        bool s = this->disable_tx(); +        _iface->poke32(FR_TX_SAMPLE_RATE_DIV, div - 1); +        _iface->poke32(FR_INTERP_RATE, rate/div - 1); +        this->restore_tx(s); + +        //update the streamer if created +        boost::shared_ptr<usrp1_send_packet_streamer> my_streamer = +            boost::dynamic_pointer_cast<usrp1_send_packet_streamer>(_tx_streamer.lock()); +        if (my_streamer.get() != NULL){ +            my_streamer->set_samp_rate(_master_clock_rate / rate); +        } +    } + +    return _master_clock_rate / rate; +} + +void usrp1_impl::update_rates(void){ +    const fs_path mb_path = "/mboards/0"; +    this->update_tick_rate(_master_clock_rate); +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){ +        _tree->access<double>(mb_path / "rx_dsps" / name / "rate" / "value").update(); +    } +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +        _tree->access<double>(mb_path / "tx_dsps" / name / "rate" / "value").update(); +    } +} + +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); + +    return (double(freq_word) / scale_factor) * _master_clock_rate; +} + +double usrp1_impl::update_tx_dsp_freq(const size_t dspno, const double freq){ +    const subdev_spec_pair_t pair = _tx_subdev_spec.at(dspno); + +    //determine the connection type and hence, the sign +    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(); +    double sign = (conn == "I" or conn == "IQ")? +1.0 : -1.0; + +    //map this DSP's subdev spec to a particular codec chip +    _dbc[pair.db_name].codec->set_duc_freq(sign*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); +} + +/*********************************************************************** + * Receive streamer + **********************************************************************/ +rx_streamer::sptr usrp1_impl::get_rx_stream(const uhd::stream_args_t &args_){ +    stream_args_t args = args_; + +    //setup defaults for unspecified values +    args.otw_format = args.otw_format.empty()? "sc16" : args.otw_format; +    args.channels.clear(); //NOTE: we have no choice about the channel mapping +    for (size_t ch = 0; ch < _rx_subdev_spec.size(); ch++){ +        args.channels.push_back(ch); +    } + +    if (args.otw_format == "sc16"){ +        _iface->poke32(FR_RX_FORMAT, 0 +            | (0 << bmFR_RX_FORMAT_SHIFT_SHIFT) +            | (16 << bmFR_RX_FORMAT_WIDTH_SHIFT) +            | bmFR_RX_FORMAT_WANT_Q +        ); +    } +    else if (args.otw_format == "sc8"){ +        _iface->poke32(FR_RX_FORMAT, 0 +            | (8 << bmFR_RX_FORMAT_SHIFT_SHIFT) +            | (8 << bmFR_RX_FORMAT_WIDTH_SHIFT) +            | bmFR_RX_FORMAT_WANT_Q +        ); +    } +    else{ +        throw uhd::value_error("USRP1 RX cannot handle requested wire format: " + args.otw_format); +    } + +    //calculate packet size +    const size_t bpp = _data_transport->get_recv_frame_size()/args.channels.size(); +    const size_t spp = bpp/convert::get_bytes_per_item(args.otw_format); + +    //make the new streamer given the samples per packet +    boost::shared_ptr<usrp1_recv_packet_streamer> my_streamer = +        boost::make_shared<usrp1_recv_packet_streamer>(spp, _soft_time_ctrl); + +    //init some streamer stuff +    my_streamer->set_tick_rate(_master_clock_rate); +    my_streamer->set_vrt_unpacker(&usrp1_bs_vrt_unpacker); +    my_streamer->set_xport_chan_get_buff(0, boost::bind( +        &uhd::transport::zero_copy_if::get_recv_buff, _io_impl->data_transport, _1 +    )); + +    //set the converter +    uhd::convert::id_type id; +    id.input_format = args.otw_format + "_item16_usrp1"; +    id.num_inputs = 1; +    id.output_format = args.cpu_format; +    id.num_outputs = args.channels.size(); +    my_streamer->set_converter(id); + +    //special scale factor change for sc8 +    if (args.otw_format == "sc8") +        my_streamer->set_scale_factor(1.0/127); + +    //save as weak ptr for update access +    _rx_streamer = my_streamer; + +    //sets all tick and samp rates on this streamer +    this->update_rates(); + +    return my_streamer; +} + +/*********************************************************************** + * Transmit streamer + **********************************************************************/ +tx_streamer::sptr usrp1_impl::get_tx_stream(const uhd::stream_args_t &args_){ +    stream_args_t args = args_; + +    //setup defaults for unspecified values +    args.otw_format = args.otw_format.empty()? "sc16" : args.otw_format; +    args.channels.clear(); //NOTE: we have no choice about the channel mapping +    for (size_t ch = 0; ch < _tx_subdev_spec.size(); ch++){ +        args.channels.push_back(ch); +    } + +    if (args.otw_format != "sc16"){ +        throw uhd::value_error("USRP1 TX cannot handle requested wire format: " + args.otw_format); +    } + +    _iface->poke32(FR_TX_FORMAT, bmFR_TX_FORMAT_16_IQ); + +    //calculate packet size +    size_t bpp = _data_transport->get_send_frame_size()/args.channels.size(); +    bpp -= alignment_padding - 1; //minus the max remainder after LUT commit +    const size_t spp = bpp/convert::get_bytes_per_item(args.otw_format); + +    //make the new streamer given the samples per packet +    boost::function<void(bool)> tx_fcn = boost::bind(&usrp1_impl::tx_stream_on_off, this, _1); +    boost::shared_ptr<usrp1_send_packet_streamer> my_streamer = +        boost::make_shared<usrp1_send_packet_streamer>(spp, _soft_time_ctrl, tx_fcn); + +    //init some streamer stuff +    my_streamer->set_tick_rate(_master_clock_rate); +    my_streamer->set_vrt_packer(&usrp1_bs_vrt_packer); +    my_streamer->set_xport_chan_get_buff(0, boost::bind( +        &usrp1_impl::io_impl::get_send_buff, _io_impl.get(), _1 +    )); + +    //set the converter +    uhd::convert::id_type id; +    id.input_format = args.cpu_format; +    id.num_inputs = args.channels.size(); +    id.output_format = args.otw_format + "_item16_usrp1"; +    id.num_outputs = 1; +    my_streamer->set_converter(id); + +    //save as weak ptr for update access +    _tx_streamer = my_streamer; + +    //sets all tick and samp rates on this streamer +    this->update_rates(); + +    return my_streamer; +} diff --git a/host/lib/usrp/usrp1/soft_time_ctrl.cpp b/host/lib/usrp/usrp1/soft_time_ctrl.cpp new file mode 100644 index 000000000..65bdc36d4 --- /dev/null +++ b/host/lib/usrp/usrp1/soft_time_ctrl.cpp @@ -0,0 +1,231 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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 "soft_time_ctrl.hpp" +#include <uhd/utils/tasks.hpp> +#include <boost/make_shared.hpp> +#include <boost/thread/condition_variable.hpp> +#include <boost/date_time/posix_time/posix_time.hpp> +#include <iostream> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; +namespace pt = boost::posix_time; + +static const time_spec_t TWIDDLE(0.0011); + +/*********************************************************************** + * Soft time control implementation + **********************************************************************/ +class soft_time_ctrl_impl : public soft_time_ctrl{ +public: + +    soft_time_ctrl_impl(const cb_fcn_type &stream_on_off): +        _nsamps_remaining(0), +        _stream_mode(stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS), +        _cmd_queue(2), +        _async_msg_queue(1000), +        _inline_msg_queue(1000), +        _stream_on_off(stream_on_off) +    { +        //synchronously spawn a new thread +        _recv_cmd_task = task::make(boost::bind(&soft_time_ctrl_impl::recv_cmd_task, this)); + +        //initialize the time to something +        this->set_time(time_spec_t(0.0)); +    } + +    /******************************************************************* +     * Time control +     ******************************************************************/ +    void set_time(const time_spec_t &time){ +        boost::mutex::scoped_lock lock(_update_mutex); +        _time_offset = time_spec_t::get_system_time() - time; +    } + +    time_spec_t get_time(void){ +        boost::mutex::scoped_lock lock(_update_mutex); +        return time_now(); +    } + +    UHD_INLINE time_spec_t time_now(void){ +        //internal get time without scoped lock +        return time_spec_t::get_system_time() - _time_offset; +    } + +    UHD_INLINE void sleep_until_time( +        boost::mutex::scoped_lock &lock, const time_spec_t &time +    ){ +        boost::condition_variable cond; +        //use a condition variable to unlock, sleep, lock +        double seconds_to_sleep = (time - time_now()).get_real_secs(); +        cond.timed_wait(lock, pt::microseconds(long(seconds_to_sleep*1e6))); +    } + +    /******************************************************************* +     * Receive control +     ******************************************************************/ +    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 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) 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; +            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(boost::make_shared<stream_cmd_t>(cmd)); +    } + +    void stream_on_off(bool enb){ +        _stream_on_off(enb); +        _nsamps_remaining = 0; +    } + +    /******************************************************************* +     * Transmit control +     ******************************************************************/ +    void send_pre(const tx_metadata_t &md, double &timeout){ +        if (not md.has_time_spec) return; + +        boost::mutex::scoped_lock lock(_update_mutex); + +        time_spec_t time_at(md.time_spec - TWIDDLE); + +        //handle late packets +        if (time_at < time_now()){ +            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; +        } + +        timeout -= (time_at - time_now()).get_real_secs(); +        sleep_until_time(lock, time_at); +    } + +    /******************************************************************* +     * Thread control +     ******************************************************************/ +    void recv_cmd_handle_cmd(const stream_cmd_t &cmd){ +        boost::mutex::scoped_lock lock(_update_mutex); + +        //handle the stream at time by sleeping +        if (not cmd.stream_now){ +            time_spec_t time_at(cmd.time_spec - TWIDDLE); +            if (time_at < time_now()){ +                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); +            } +        } + +        //When to stop streaming: +        //Stop streaming when the command is a stop and streaming. +        if (cmd.stream_mode == stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS +           and _stream_mode != stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS +        ) stream_on_off(false); + +        //When to start streaming: +        //Start streaming when the command is not a stop and not streaming. +        if (cmd.stream_mode != stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS +           and _stream_mode == stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS +        ) stream_on_off(true); + +        //update the state +        _nsamps_remaining += cmd.num_samps; +        _stream_mode = cmd.stream_mode; +    } + +    void recv_cmd_task(void){ //task is looped +        boost::shared_ptr<stream_cmd_t> cmd; +        _cmd_queue.pop_with_wait(cmd); +        recv_cmd_handle_cmd(*cmd); +    } + +    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; +    } + +    void stop(void){ +        _recv_cmd_task.reset(); +    } + +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::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; +    task::sptr _recv_cmd_task; +}; + +/*********************************************************************** + * Soft time control factor + **********************************************************************/ +soft_time_ctrl::sptr soft_time_ctrl::make(const cb_fcn_type &stream_on_off){ +    return sptr(new soft_time_ctrl_impl(stream_on_off)); +} diff --git a/host/lib/usrp/usrp1/soft_time_ctrl.hpp b/host/lib/usrp/usrp1/soft_time_ctrl.hpp new file mode 100644 index 000000000..f418ec35a --- /dev/null +++ b/host/lib/usrp/usrp1/soft_time_ctrl.hpp @@ -0,0 +1,77 @@ +// +// Copyright 2011-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// 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_USRP1_SOFT_TIME_CTRL_HPP +#define INCLUDED_LIBUHD_USRP_USRP1_SOFT_TIME_CTRL_HPP + +#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> + +namespace uhd{ namespace usrp{ + +/*! + * The soft time control emulates some of the + * advanced streaming capabilities of the later USRP models. + * Soft time control uses the system time to emulate + * timed transmits, timed receive commands, device time, + * and inline and async error messages. + */ +class soft_time_ctrl : boost::noncopyable{ +public: +    typedef boost::shared_ptr<soft_time_ctrl> sptr; +    typedef boost::function<void(bool)> cb_fcn_type; + +    /*! +     * Make a new soft time control. +     * \param stream_on_off a function to enable/disable rx +     * \return a new soft time control object +     */ +    static sptr make(const cb_fcn_type &stream_on_off); + +    //! Set the current time +    virtual void set_time(const time_spec_t &time) = 0; + +    //! Get the current time +    virtual time_spec_t get_time(void) = 0; + +    //! Call after the internal recv function +    virtual size_t recv_post(rx_metadata_t &md, const size_t nsamps) = 0; + +    //! Call before the internal send function +    virtual void 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; + +    //! Stops threads before deconstruction to avoid race conditions +    virtual void stop(void) = 0; +}; + +}} //namespace + +#endif /* INCLUDED_LIBUHD_USRP_USRP1_SOFT_TIME_CTRL_HPP */ 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..d86a7a809 --- /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 << 0) | (adc_for_q << 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 + * +-----------------------+-------+-------+-------+-------+-+-----+ + * |      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 << 0) | (chn_for_q << 4); +} + +/*! + *    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 new file mode 100644 index 000000000..c790aecb4 --- /dev/null +++ b/host/lib/usrp/usrp1/usrp1_iface.cpp @@ -0,0 +1,205 @@ +// +// 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_iface.hpp" +#include "usrp_commands.h" +#include <uhd/utils/log.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/byteswap.hpp> +#include <boost/format.hpp> +#include <stdexcept> +#include <iomanip> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; + +class usrp1_iface_impl : public usrp1_iface{ +public: +    /******************************************************************* +     * Structors +     ******************************************************************/ +    usrp1_iface_impl(uhd::usrp::fx2_ctrl::sptr ctrl_transport) +    { +        _ctrl_transport = ctrl_transport; +    } + +    ~usrp1_iface_impl(void) +    { +        /* NOP */ +    } + +    /******************************************************************* +     * Peek and Poke +     ******************************************************************/ +    void poke32(boost::uint32_t addr, boost::uint32_t value) +    { +        boost::uint32_t swapped = uhd::htonx(value); + +        UHD_LOGV(always) +            << "poke32(" +            << std::dec << std::setw(2) << addr << ", 0x" +            << std::hex << std::setw(8) << value << ")" << std::endl +        ; + +        boost::uint8_t w_index_h = SPI_ENABLE_FPGA & 0xff; +        boost::uint8_t w_index_l = (SPI_FMT_MSB | SPI_FMT_HDR_1) & 0xff; + +        int ret =_ctrl_transport->usrp_control_write( +                                          VRQ_SPI_WRITE, +                                          addr & 0x7f, +                                          (w_index_h << 8) | (w_index_l << 0), +                                          (unsigned char*) &swapped, +                                          sizeof(boost::uint32_t)); + +        if (ret < 0) throw uhd::io_error("USRP1: failed control write"); +    } + +    boost::uint32_t peek32(boost::uint32_t addr) +    { +        UHD_LOGV(always) +            << "peek32(" +            << std::dec << std::setw(2) << addr << ")" << std::endl +        ; + +        boost::uint32_t value_out; + +        boost::uint8_t w_index_h = SPI_ENABLE_FPGA & 0xff; +        boost::uint8_t w_index_l = (SPI_FMT_MSB | SPI_FMT_HDR_1) & 0xff; + +        int ret = _ctrl_transport->usrp_control_read( +                                          VRQ_SPI_READ, +                                          0x80 | (addr & 0x7f), +                                          (w_index_h << 8) | (w_index_l << 0), +                                          (unsigned char*) &value_out, +                                          sizeof(boost::uint32_t)); + +        if (ret < 0) throw uhd::io_error("USRP1: failed control read"); + +        return uhd::ntohx(value_out); +    } +     +    void poke16(boost::uint32_t, boost::uint16_t) { +        throw uhd::not_implemented_error("Unhandled command poke16()"); +    } +     +    boost::uint16_t peek16(boost::uint32_t) { +        throw uhd::not_implemented_error("Unhandled command peek16()"); +        return 0; +    } + +    /******************************************************************* +     * I2C +     ******************************************************************/ +    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){ +        return _ctrl_transport->read_i2c(addr, num_bytes); +    } + +    /******************************************************************* +     * SPI +     * +     * For non-readback transactions use the SPI_WRITE command, which is +     * simpler and uses the USB control buffer for OUT data. No data +     * needs to be returned. +     * +     * For readback transactions use SPI_TRANSACT, which places up to +     * 4 bytes of OUT data in the device request fields and uses the +     * control buffer for IN data. +     ******************************************************************/ +    boost::uint32_t transact_spi(int which_slave, +                                 const spi_config_t &, +                                 boost::uint32_t bits, +                                 size_t num_bits, +                                 bool readback) +    { +        UHD_LOGV(always) +            << "transact_spi: " << std::endl +            << "  slave: " << which_slave << std::endl +            << "  bits: " << bits << std::endl +            << "  num_bits: " << num_bits << std::endl +            << "  readback: " << readback << std::endl +        ; +        UHD_ASSERT_THROW((num_bits <= 32) && !(num_bits % 8)); +        size_t num_bytes = num_bits / 8; + +        if (readback) { +            unsigned char buff[4] = { +                (bits >> 0) & 0xff, (bits >> 8) & 0xff, +                (bits >> 16) & 0xff, (bits >> 24) & 0xff +            }; +            //conditions where there are two header bytes +            if (num_bytes >= 3 and buff[num_bytes-1] != 0 and buff[num_bytes-2] != 0 and buff[num_bytes-3] == 0){ +                if (int(num_bytes-2) != _ctrl_transport->usrp_control_read( +                    VRQ_SPI_READ, (buff[num_bytes-1] << 8) | (buff[num_bytes-2] << 0), +                    (which_slave << 8) | SPI_FMT_MSB | SPI_FMT_HDR_2, +                    buff, num_bytes-2 +                )) throw uhd::io_error("USRP1: failed SPI readback transaction"); +            } + +            //conditions where there is one header byte +            else if (num_bytes >= 2 and buff[num_bytes-1] != 0 and buff[num_bytes-2] == 0){ +                if (int(num_bytes-1) != _ctrl_transport->usrp_control_read( +                    VRQ_SPI_READ, buff[num_bytes-1], +                    (which_slave << 8) | SPI_FMT_MSB | SPI_FMT_HDR_1, +                    buff, num_bytes-1 +                )) throw uhd::io_error("USRP1: failed SPI readback transaction"); +            } +            else{ +                throw uhd::io_error("USRP1: invalid input data for SPI readback"); +            } +            boost::uint32_t val = (((boost::uint32_t)buff[0]) <<  0) | +                                  (((boost::uint32_t)buff[1]) <<  8) | +                                  (((boost::uint32_t)buff[2]) << 16) | +                                  (((boost::uint32_t)buff[3]) << 24); +            return val;  +        } +        else { +            // Byteswap on num_bytes +            unsigned char buff[4] = { 0 }; +            for (size_t i = 1; i <= num_bytes; i++) +                buff[num_bytes - i] = (bits >> ((i - 1) * 8)) & 0xff; + +            boost::uint8_t w_index_h = which_slave & 0xff; +            boost::uint8_t w_index_l = (SPI_FMT_MSB | SPI_FMT_HDR_0) & 0xff; + +            int ret =_ctrl_transport->usrp_control_write( +                                          VRQ_SPI_WRITE, +                                          0x00, +                                          (w_index_h << 8) | (w_index_l << 0), +                                          buff, num_bytes); + +            if (ret < 0) throw uhd::io_error("USRP1: failed SPI transaction"); + +            return 0; +        } +    } + +private: +    uhd::usrp::fx2_ctrl::sptr _ctrl_transport; +}; + +/*********************************************************************** + * Public Make Function + **********************************************************************/ +usrp1_iface::sptr usrp1_iface::make(uhd::usrp::fx2_ctrl::sptr ctrl_transport) +{ +    return sptr(new usrp1_iface_impl(ctrl_transport)); +} diff --git a/host/lib/usrp/usrp1/usrp1_iface.hpp b/host/lib/usrp/usrp1/usrp1_iface.hpp new file mode 100644 index 000000000..c1ac34f25 --- /dev/null +++ b/host/lib/usrp/usrp1/usrp1_iface.hpp @@ -0,0 +1,44 @@ +// +// 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_IFACE_HPP +#define INCLUDED_USRP1_IFACE_HPP + +#include "fx2_ctrl.hpp" +#include "wb_iface.hpp" +#include <uhd/types/serial.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> + +/*! + * The usrp1 interface class: + * Provides a set of functions to implementation layer. + * Including spi, peek, poke, control... + */ +class usrp1_iface : public wb_iface, public uhd::i2c_iface, public uhd::spi_iface, boost::noncopyable{ +public: +    typedef boost::shared_ptr<usrp1_iface> sptr; + +    /*! +     * 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); +}; + +#endif /* INCLUDED_USRP1_IFACE_HPP */ diff --git a/host/lib/usrp/usrp1/usrp1_impl.cpp b/host/lib/usrp/usrp1/usrp1_impl.cpp new file mode 100644 index 000000000..ffe25b81e --- /dev/null +++ b/host/lib/usrp/usrp1/usrp1_impl.cpp @@ -0,0 +1,499 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "usrp1_impl.hpp" +#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/utils/msg.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/images.hpp> +#include <boost/format.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/filesystem.hpp> +#include <boost/thread/thread.hpp> +#include <boost/lexical_cast.hpp> +#include <boost/math/special_functions/round.hpp> +#include <cstdio> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; + +const boost::uint16_t USRP1_VENDOR_ID  = 0xfffe; +const boost::uint16_t USRP1_PRODUCT_ID = 0x0002; +const boost::uint16_t FX2_VENDOR_ID    = 0x04b4; +const boost::uint16_t FX2_PRODUCT_ID   = 0x8613; +static const boost::posix_time::milliseconds REENUMERATION_TIMEOUT_MS(3000); + +const std::vector<usrp1_impl::dboard_slot_t> usrp1_impl::_dboard_slots = boost::assign::list_of +    (usrp1_impl::DBOARD_SLOT_A)(usrp1_impl::DBOARD_SLOT_B) +; + +/*********************************************************************** + * Discovery + **********************************************************************/ +static device_addrs_t usrp1_find(const device_addr_t &hint) +{ +    device_addrs_t usrp1_addrs; + +    //return an empty list of addresses when type is set to non-usrp1 +    if (hint.has_key("type") and hint["type"] != "usrp1") return usrp1_addrs; + +    //Return an empty list of addresses when an address is specified, +    //since an address is intended for a different, non-USB, device. +    if (hint.has_key("addr")) return usrp1_addrs; + +    unsigned int vid, pid; + +    if(hint.has_key("vid") && hint.has_key("pid") && hint.has_key("type") && hint["type"] == "usrp1") { +        sscanf(hint.get("vid").c_str(), "%x", &vid); +        sscanf(hint.get("pid").c_str(), "%x", &pid); +    } else { +        vid = USRP1_VENDOR_ID; +        pid = USRP1_PRODUCT_ID; +    } + +    // Important note: +    // The get device list calls are nested inside the for loop. +    // This allows the usb guts to decontruct when not in use, +    // so that re-enumeration after fw load can occur successfully. +    // This requirement is a courtesy of libusb1.0 on windows. + +    //find the usrps and load firmware +    size_t found = 0; +    BOOST_FOREACH(usb_device_handle::sptr handle, usb_device_handle::get_device_list(vid, pid)) { +        //extract the firmware path for the USRP1 +        std::string usrp1_fw_image; +        try{ +            usrp1_fw_image = find_image_path(hint.get("fw", "usrp1_fw.ihx")); +        } +        catch(...){ +            UHD_MSG(warning) << boost::format("Could not locate USRP1 firmware. %s") % print_images_error(); +        } +        UHD_LOG << "USRP1 firmware image: " << usrp1_fw_image << std::endl; + +        usb_control::sptr control; +        try{control = usb_control::make(handle, 0);} +        catch(const uhd::exception &){continue;} //ignore claimed + +        fx2_ctrl::make(control)->usrp_load_firmware(usrp1_fw_image); +        found++; +    } + +    //get descriptors again with serial number, but using the initialized VID/PID now since we have firmware +    vid = USRP1_VENDOR_ID; +    pid = USRP1_PRODUCT_ID; + +    const boost::system_time timeout_time = boost::get_system_time() + REENUMERATION_TIMEOUT_MS; + +    //search for the device until found or timeout +    while (boost::get_system_time() < timeout_time and usrp1_addrs.empty() and found != 0) +    { +        BOOST_FOREACH(usb_device_handle::sptr handle, usb_device_handle::get_device_list(vid, pid)) +        { +            usb_control::sptr control; +            try{control = usb_control::make(handle, 0);} +            catch(const uhd::exception &){continue;} //ignore claimed + +            fx2_ctrl::sptr fx2_ctrl = fx2_ctrl::make(control); +            const mboard_eeprom_t mb_eeprom(*fx2_ctrl, USRP1_EEPROM_MAP_KEY); +            device_addr_t new_addr; +            new_addr["type"] = "usrp1"; +            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 ( +                (not hint.has_key("name")   or hint["name"]   == new_addr["name"]) and +                (not hint.has_key("serial") or hint["serial"] == new_addr["serial"]) +            ){ +                usrp1_addrs.push_back(new_addr); +            } +        } +    } + +    return usrp1_addrs; +} + +/*********************************************************************** + * 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 +    std::string usrp1_fpga_image = find_image_path( +        device_addr.get("fpga", "usrp1_fpga.rbf") +    ); +    UHD_LOG << "USRP1 FPGA image: " << usrp1_fpga_image << std::endl; + +    //try to match the given device address with something on the USB bus +    std::vector<usb_device_handle::sptr> device_list = +        usb_device_handle::get_device_list(USRP1_VENDOR_ID, USRP1_PRODUCT_ID); + +    //locate the matching handle in the device list +    usb_device_handle::sptr handle; +    BOOST_FOREACH(usb_device_handle::sptr dev_handle, device_list) { +        if (dev_handle->get_serial() == device_addr["serial"]){ +            handle = dev_handle; +            break; +        } +    } +    UHD_ASSERT_THROW(handle.get() != NULL); //better be found + +    //////////////////////////////////////////////////////////////////// +    // Create controller objects +    //////////////////////////////////////////////////////////////////// +    //usb_control::sptr usb_ctrl = usb_control::make(handle); +    _fx2_ctrl = fx2_ctrl::make(usb_control::make(handle, 0)); +    _fx2_ctrl->usrp_load_fpga(usrp1_fpga_image); +    _fx2_ctrl->usrp_init(); +    _data_transport = usb_zero_copy::make( +        handle,        // identifier +        2, 6,          // IN interface, endpoint +        1, 2,          // OUT interface, endpoint +        device_addr    // param hints +    ); +    _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); + +    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 +    //////////////////////////////////////////////////////////////////// +    _rx_dc_offset_shadow = 0; +    _tree = property_tree::make(); +    _tree->create<std::string>("/name").set("USRP1 Device"); +    const fs_path mb_path = "/mboards/0"; +    _tree->create<std::string>(mb_path / "name").set("USRP1"); +    _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, USRP1_EEPROM_MAP_KEY); +    _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; +    if (device_addr.has_key("mcr")){ +        try{ +            _master_clock_rate = boost::lexical_cast<double>(device_addr["mcr"]); +        } +        catch(const std::exception &e){ +            UHD_MSG(error) << "Error parsing FPGA clock rate from device address: " << e.what() << std::endl; +        } +    } +    else if (not mb_eeprom["mcr"].empty()){ +        try{ +            _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") +        .subscribe(boost::bind(&usrp1_impl::update_tick_rate, this, _1)) +        .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 fs_path rx_codec_path = mb_path / "rx_codecs" / db; +        const fs_path 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)); +    } + +    //////////////////////////////////////////////////////////////////// +    // 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") +        .set(subdev_spec_t()) +        .subscribe(boost::bind(&usrp1_impl::update_rx_subdev_spec, this, _1)); +    _tree->create<subdev_spec_t>(mb_path / "tx_subdev_spec") +        .set(subdev_spec_t()) +        .subscribe(boost::bind(&usrp1_impl::update_tx_subdev_spec, this, _1)); + +    BOOST_FOREACH(const std::string &db, _dbc.keys()){ +        const fs_path rx_fe_path = mb_path / "rx_frontends" / db; +        _tree->create<std::complex<double> >(rx_fe_path / "dc_offset" / "value") +            .coerce(boost::bind(&usrp1_impl::set_rx_dc_offset, this, db, _1)) +            .set(std::complex<double>(0.0, 0.0)); +        _tree->create<bool>(rx_fe_path / "dc_offset" / "enable") +            .subscribe(boost::bind(&usrp1_impl::set_enb_rx_dc_offset, this, db, _1)) +            .set(true); +    } + +    //////////////////////////////////////////////////////////////////// +    // create rx dsp control objects +    //////////////////////////////////////////////////////////////////// +    _tree->create<int>(mb_path / "rx_dsps"); //dummy in case we have none +    for (size_t dspno = 0; dspno < get_num_ddcs(); dspno++){ +        fs_path rx_dsp_path = mb_path / str(boost::format("rx_dsps/%u") % dspno); +        _tree->create<meta_range_t>(rx_dsp_path / "rate/range") +            .publish(boost::bind(&usrp1_impl::get_rx_dsp_host_rates, this)); +        _tree->create<double>(rx_dsp_path / "rate/value") +            .set(1e6) //some default rate +            .coerce(boost::bind(&usrp1_impl::update_rx_samp_rate, this, dspno, _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") +            .publish(boost::bind(&usrp1_impl::get_rx_dsp_freq_range, this)); +        _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)); +        } +    } + +    //////////////////////////////////////////////////////////////////// +    // create tx dsp control objects +    //////////////////////////////////////////////////////////////////// +    _tree->create<int>(mb_path / "tx_dsps"); //dummy in case we have none +    for (size_t dspno = 0; dspno < get_num_ducs(); dspno++){ +        fs_path tx_dsp_path = mb_path / str(boost::format("tx_dsps/%u") % dspno); +        _tree->create<meta_range_t>(tx_dsp_path / "rate/range") +            .publish(boost::bind(&usrp1_impl::get_tx_dsp_host_rates, this)); +        _tree->create<double>(tx_dsp_path / "rate/value") +            .set(1e6) //some default rate +            .coerce(boost::bind(&usrp1_impl::update_tx_samp_rate, this, dspno, _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") +            .publish(boost::bind(&usrp1_impl::get_tx_dsp_freq_range, this)); +    } + +    //////////////////////////////////////////////////////////////////// +    // 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, tx_db_eeprom.id, gdb_eeprom.id, +            _dbc[db].dboard_iface, _tree->subtree(mb_path / "dboards" / db) +        ); + +        //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 + ":" + _tree->list(mb_path / "dboards" / db / "rx_frontends").at(0)); +        } +        if (tx_db_eeprom.id != dboard_id_t::none() or _tx_subdev_spec.empty()){ +            _tx_subdev_spec = subdev_spec_t(db + ":" + _tree->list(mb_path / "dboards" / db / "tx_frontends").at(0)); +        } +    } + +    //initialize io handling +    this->io_init(); + +    //////////////////////////////////////////////////////////////////// +    // do some post-init tasks +    //////////////////////////////////////////////////////////////////// +    this->update_rates(); + +    //reset cordic rates and their properties to zero +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){ +        _tree->access<double>(mb_path / "rx_dsps" / name / "freq" / "value").set(0.0); +    } + +    if (_tree->list(mb_path / "rx_dsps").size() > 0) +        _tree->access<subdev_spec_t>(mb_path / "rx_subdev_spec").set(_rx_subdev_spec); +    if (_tree->list(mb_path / "tx_dsps").size() > 0) +        _tree->access<subdev_spec_t>(mb_path / "tx_subdev_spec").set(_tx_subdev_spec); +  +} + +usrp1_impl::~usrp1_impl(void){ +    UHD_SAFE_CALL( +        this->enable_rx(false); +        this->enable_tx(false); +    ) +    _soft_time_ctrl->stop(); //stops cmd task before proceeding +    _io_impl.reset(); //stops vandal before other stuff gets deconstructed +} + +/*! + * 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; +} + +/*********************************************************************** + * Properties callback methods below + **********************************************************************/ +void usrp1_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){ +    mb_eeprom.commit(*_fx2_ctrl, USRP1_EEPROM_MAP_KEY); +} + +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'); +} + +uhd::meta_range_t usrp1_impl::get_rx_dsp_freq_range(void){ +    return meta_range_t(-_master_clock_rate/2, +_master_clock_rate/2); +} + +uhd::meta_range_t usrp1_impl::get_tx_dsp_freq_range(void){ +    //magic scalar comes from codec control: +    return meta_range_t(-_master_clock_rate*0.6875, +_master_clock_rate*0.6875); +} + +void usrp1_impl::set_enb_rx_dc_offset(const std::string &db, const bool enb){ +    const size_t shift = (db == "A")? 0 : 2; +    _rx_dc_offset_shadow &= ~(0x3 << shift); //clear bits +    _rx_dc_offset_shadow |= ((enb)? 0x3 : 0x0) << shift; +    _iface->poke32(FR_DC_OFFSET_CL_EN, _rx_dc_offset_shadow & 0xf); +} + +std::complex<double> usrp1_impl::set_rx_dc_offset(const std::string &db, const std::complex<double> &offset){ +    const boost::int32_t i_off = boost::math::iround(offset.real() * (1ul << 31)); +    const boost::int32_t q_off = boost::math::iround(offset.imag() * (1ul << 31)); + +    if (db == "A"){ +        _iface->poke32(FR_ADC_OFFSET_0, i_off); +        _iface->poke32(FR_ADC_OFFSET_1, q_off); +    } + +    if (db == "B"){ +        _iface->poke32(FR_ADC_OFFSET_2, i_off); +        _iface->poke32(FR_ADC_OFFSET_3, q_off); +    } + +    return std::complex<double>(double(i_off) * (1ul << 31), double(q_off) * (1ul << 31)); +} diff --git a/host/lib/usrp/usrp1/usrp1_impl.hpp b/host/lib/usrp/usrp1/usrp1_impl.hpp new file mode 100644 index 000000000..bdef50ec1 --- /dev/null +++ b/host/lib/usrp/usrp1/usrp1_impl.hpp @@ -0,0 +1,182 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "usrp1_iface.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 <uhd/transport/usb_zero_copy.hpp> +#include <boost/foreach.hpp> +#include <boost/weak_ptr.hpp> +#include <complex> + +#ifndef INCLUDED_USRP1_IMPL_HPP +#define INCLUDED_USRP1_IMPL_HPP + +static const std::string USRP1_EEPROM_MAP_KEY = "B000"; + +/*! + * USRP1 implementation guts: + * The implementation details are encapsulated here. + * Handles properties on the mboard, dboard, dsps... + */ +class usrp1_impl : public uhd::device { +public: +    //! used everywhere to differentiate slots/sides... +    enum dboard_slot_t{ +        DBOARD_SLOT_A = 'A', +        DBOARD_SLOT_B = 'B' +    }; +    //and a way to enumerate through a list of the above... +    static const std::vector<dboard_slot_t> _dboard_slots; + +    //structors +    usrp1_impl(const uhd::device_addr_t &); +    ~usrp1_impl(void); + +    //the io interface +    uhd::rx_streamer::sptr get_rx_stream(const uhd::stream_args_t &args); +    uhd::tx_streamer::sptr get_tx_stream(const uhd::stream_args_t &args); +    bool recv_async_msg(uhd::async_metadata_t &, double); + +private: +    uhd::property_tree::sptr _tree; + +    //device properties interface +    uhd::property_tree::sptr get_tree(void) const{ +        return _tree; +    } + +    //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; + +    double _master_clock_rate; //clock rate shadow + +    //weak pointers to streamers for update purposes +    boost::weak_ptr<uhd::rx_streamer> _rx_streamer; +    boost::weak_ptr<uhd::tx_streamer> _tx_streamer; + +    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(size_t dspno, const double); +    double update_tx_samp_rate(size_t dspno, const double); +    void update_rates(void); +    double update_rx_dsp_freq(const size_t, const double); +    double update_tx_dsp_freq(const size_t, const double); +    void update_tick_rate(const double rate); +    uhd::meta_range_t get_rx_dsp_freq_range(void); +    uhd::meta_range_t get_tx_dsp_freq_range(void); +    uhd::meta_range_t get_rx_dsp_host_rates(void); +    uhd::meta_range_t get_tx_dsp_host_rates(void); +    size_t _rx_dc_offset_shadow; +    void set_enb_rx_dc_offset(const std::string &db, const bool); +    std::complex<double> set_rx_dc_offset(const std::string &db, const std::complex<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); + +    //channel mapping shadows +    uhd::usrp::subdev_spec_t _rx_subdev_spec, _tx_subdev_spec; + +    //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(void); + +    //handle the enables +    bool _rx_enabled, _tx_enabled; +    void enable_rx(bool enb){ +        _rx_enabled = enb; +        _fx2_ctrl->usrp_rx_enable(enb); +    } +    void enable_tx(bool enb){ +        _tx_enabled = enb; +        _fx2_ctrl->usrp_tx_enable(enb); +        BOOST_FOREACH(const std::string &key, _dbc.keys()) +        { +            _dbc[key].codec->enable_tx_digital(enb); +        } +    } + +    //conditionally disable and enable rx +    bool disable_rx(void){ +        if (_rx_enabled){ +            enable_rx(false); +            return true; +        } +        return false; +    } +    void restore_rx(bool last){ +        if (last != _rx_enabled){ +            enable_rx(last); +        } +    } + +    //conditionally disable and enable tx +    bool disable_tx(void){ +        if (_tx_enabled){ +            enable_tx(false); +            return true; +        } +        return false; +    } +    void restore_tx(bool last){ +        if (last != _tx_enabled){ +            enable_tx(last); +        } +    } +}; + +#endif /* INCLUDED_USRP1_IMPL_HPP */ diff --git a/host/lib/usrp/usrp2/CMakeLists.txt b/host/lib/usrp/usrp2/CMakeLists.txt new file mode 100644 index 000000000..da39d9df1 --- /dev/null +++ b/host/lib/usrp/usrp2/CMakeLists.txt @@ -0,0 +1,37 @@ +# +# Copyright 2011-2012 Ettus Research LLC +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# 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 +######################################################################## + +######################################################################## +# Conditionally configure the USRP2 support +######################################################################## +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}/codec_ctrl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/dboard_iface.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/io_impl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/usrp2_iface.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/usrp2_impl.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/usrp2_fifo_ctrl.cpp +    ) +ENDIF(ENABLE_USRP2) diff --git a/host/lib/usrp/usrp2/clock_ctrl.cpp b/host/lib/usrp/usrp2/clock_ctrl.cpp new file mode 100644 index 000000000..0ae3b0bd8 --- /dev/null +++ b/host/lib/usrp/usrp2/clock_ctrl.cpp @@ -0,0 +1,391 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "clock_ctrl.hpp" +#include "ad9510_regs.hpp" +#include "usrp2_regs.hpp" //spi slave constants +#include "usrp2_clk_regs.hpp" +#include <uhd/utils/safe_call.hpp> +#include <uhd/utils/assert_has.hpp> +#include <boost/cstdint.hpp> +#include <boost/lexical_cast.hpp> +#include <boost/math/special_functions/round.hpp> +#include <iostream> + +using namespace uhd; + +static const bool enb_test_clk = false; + +/*! + * A usrp2 clock control specific to the ad9510 ic. + */ +class usrp2_clock_ctrl_impl : public usrp2_clock_ctrl{ +public: +    usrp2_clock_ctrl_impl(usrp2_iface::sptr iface, uhd::spi_iface::sptr spiface){ +        _iface = iface; +        _spiface = spiface; +        clk_regs = usrp2_clk_regs_t(_iface->get_rev()); + +        _ad9510_regs.cp_current_setting = ad9510_regs_t::CP_CURRENT_SETTING_3_0MA; +        this->write_reg(clk_regs.pll_3); + +        // Setup the clock registers to 100MHz: +        //  This was already done by the firmware (or the host couldnt communicate). +        //  We could remove this part, and just leave it to the firmware. +        //  But why not leave it in for those who want to mess with clock settings? +        //  100mhz = 10mhz/R * (P*B + A) + +        _ad9510_regs.pll_power_down = ad9510_regs_t::PLL_POWER_DOWN_NORMAL; +        _ad9510_regs.prescaler_value = ad9510_regs_t::PRESCALER_VALUE_DIV2; +        this->write_reg(clk_regs.pll_4); + +        _ad9510_regs.acounter = 0; +        this->write_reg(clk_regs.acounter); + +        _ad9510_regs.bcounter_msb = 0; +        _ad9510_regs.bcounter_lsb = 5; +        this->write_reg(clk_regs.bcounter_msb); +        this->write_reg(clk_regs.bcounter_lsb); + +        _ad9510_regs.ref_counter_msb = 0; +        _ad9510_regs.ref_counter_lsb = 1; // r divider = 1 +        this->write_reg(clk_regs.ref_counter_msb); +        this->write_reg(clk_regs.ref_counter_lsb); + +        /* regs will be updated in commands below */ + +        this->enable_external_ref(false); +        this->enable_rx_dboard_clock(false); +        this->enable_tx_dboard_clock(false); +        this->enable_mimo_clock_out(false); + +        /* private clock enables, must be set here */ +        this->enable_dac_clock(true); +        this->enable_adc_clock(true); +        this->enable_test_clock(enb_test_clk); +    } + +    ~usrp2_clock_ctrl_impl(void){UHD_SAFE_CALL( +        //power down clock outputs +        this->enable_external_ref(false); +        this->enable_rx_dboard_clock(false); +        this->enable_tx_dboard_clock(false); +        this->enable_dac_clock(false); +        this->enable_adc_clock(false); +        this->enable_mimo_clock_out(false); +        this->enable_test_clock(false); +    )} + +    void enable_mimo_clock_out(bool enb){ +        //calculate the low and high dividers +        size_t divider = size_t(this->get_master_clock_rate()/10e6); +        size_t high = divider/2; +        size_t low = divider - high; + +        switch(clk_regs.exp){ +        case 2: //U2 rev 3 +            _ad9510_regs.power_down_lvpecl_out2 = enb? +                ad9510_regs_t::POWER_DOWN_LVPECL_OUT2_NORMAL : +                ad9510_regs_t::POWER_DOWN_LVPECL_OUT2_SAFE_PD; +            _ad9510_regs.output_level_lvpecl_out2 = ad9510_regs_t::OUTPUT_LEVEL_LVPECL_OUT2_810MV; +            //set the registers (divider - 1) +            _ad9510_regs.divider_low_cycles_out2 = low - 1; +            _ad9510_regs.divider_high_cycles_out2 = high - 1; +            _ad9510_regs.bypass_divider_out2 = 0; +            break; + +        case 5: //U2 rev 4 +            _ad9510_regs.power_down_lvds_cmos_out5 = enb? 0 : 1; +            _ad9510_regs.lvds_cmos_select_out5 = ad9510_regs_t::LVDS_CMOS_SELECT_OUT5_LVDS; +            _ad9510_regs.output_level_lvds_out5 = ad9510_regs_t::OUTPUT_LEVEL_LVDS_OUT5_1_75MA; +            //set the registers (divider - 1) +            _ad9510_regs.divider_low_cycles_out5 = low - 1; +            _ad9510_regs.divider_high_cycles_out5 = high - 1; +            _ad9510_regs.bypass_divider_out5 = 0; +            break; +             +        case 6: //U2+ +            _ad9510_regs.power_down_lvds_cmos_out6 = enb? 0 : 1; +            _ad9510_regs.lvds_cmos_select_out6 = ad9510_regs_t::LVDS_CMOS_SELECT_OUT6_LVDS; +            _ad9510_regs.output_level_lvds_out6 = ad9510_regs_t::OUTPUT_LEVEL_LVDS_OUT6_1_75MA; +            //set the registers (divider - 1) +            _ad9510_regs.divider_low_cycles_out6 = low - 1; +            _ad9510_regs.divider_high_cycles_out6 = high - 1; +            _ad9510_regs.bypass_divider_out5 = 0; +            break; + +        default: +            break; +        } +        this->write_reg(clk_regs.output(clk_regs.exp)); +        this->write_reg(clk_regs.div_lo(clk_regs.exp)); +        this->update_regs(); +    } + +    //uses output clock 7 (cmos) +    void enable_rx_dboard_clock(bool enb){ +        switch(_iface->get_rev()) { +            case usrp2_iface::USRP_N200_R4: +            case usrp2_iface::USRP_N210_R4: +                _ad9510_regs.power_down_lvds_cmos_out7 = enb? 0 : 1; +                _ad9510_regs.lvds_cmos_select_out7 = ad9510_regs_t::LVDS_CMOS_SELECT_OUT7_LVDS; +                _ad9510_regs.output_level_lvds_out7 = ad9510_regs_t::OUTPUT_LEVEL_LVDS_OUT7_1_75MA; +                this->write_reg(clk_regs.output(clk_regs.rx_db)); +                this->update_regs(); +                break; +            default: +                _ad9510_regs.power_down_lvds_cmos_out7 = enb? 0 : 1; +                _ad9510_regs.lvds_cmos_select_out7 = ad9510_regs_t::LVDS_CMOS_SELECT_OUT7_CMOS; +                _ad9510_regs.output_level_lvds_out7 = ad9510_regs_t::OUTPUT_LEVEL_LVDS_OUT7_1_75MA; +                this->write_reg(clk_regs.output(clk_regs.rx_db)); +                this->update_regs(); +                break; +        } +    } + +    void set_rate_rx_dboard_clock(double rate){ +        assert_has(get_rates_rx_dboard_clock(), rate, "rx dboard clock rate"); +        size_t divider = size_t(get_master_clock_rate()/rate); +        //bypass when the divider ratio is one +        _ad9510_regs.bypass_divider_out7 = (divider == 1)? 1 : 0; +        //calculate the low and high dividers +        size_t high = divider/2; +        size_t low = divider - high; +        //set the registers (divider - 1) +        _ad9510_regs.divider_low_cycles_out7 = low - 1; +        _ad9510_regs.divider_high_cycles_out7 = high - 1; +        //write the registers +        this->write_reg(clk_regs.div_lo(clk_regs.rx_db)); +        this->write_reg(clk_regs.div_hi(clk_regs.rx_db)); +        this->update_regs(); +    } + +    std::vector<double> get_rates_rx_dboard_clock(void){ +        std::vector<double> rates; +        for (size_t i = 1; i <= 16+16; i++) rates.push_back(get_master_clock_rate()/i); +        return rates; +    } + +    //uses output clock 6 (cmos) on USRP2, output clock 5 (cmos) on N200/N210 r3, +    //and output clock 5 (lvds) on N200/N210 r4 +    void enable_tx_dboard_clock(bool enb){ +        switch(_iface->get_rev()) { +        case usrp2_iface::USRP_N200_R4: +        case usrp2_iface::USRP_N210_R4: +          _ad9510_regs.power_down_lvds_cmos_out5 = enb? 0 : 1; +          _ad9510_regs.lvds_cmos_select_out5 = ad9510_regs_t::LVDS_CMOS_SELECT_OUT5_LVDS; +          _ad9510_regs.output_level_lvds_out5 = ad9510_regs_t::OUTPUT_LEVEL_LVDS_OUT5_1_75MA; +          break; +        case usrp2_iface::USRP_N200: +        case usrp2_iface::USRP_N210: +          _ad9510_regs.power_down_lvds_cmos_out5 = enb? 0 : 1; +          _ad9510_regs.lvds_cmos_select_out5 = ad9510_regs_t::LVDS_CMOS_SELECT_OUT5_CMOS; +          _ad9510_regs.output_level_lvds_out5 = ad9510_regs_t::OUTPUT_LEVEL_LVDS_OUT5_1_75MA; +          break; +        case usrp2_iface::USRP2_REV3: +        case usrp2_iface::USRP2_REV4: +          _ad9510_regs.power_down_lvds_cmos_out6 = enb? 0 : 1; +          _ad9510_regs.lvds_cmos_select_out6 = ad9510_regs_t::LVDS_CMOS_SELECT_OUT6_CMOS; +          _ad9510_regs.output_level_lvds_out6 = ad9510_regs_t::OUTPUT_LEVEL_LVDS_OUT6_1_75MA; +          break; + +        default: +          //throw uhd::not_implemented_error("enable_tx_dboard_clock: unknown hardware version"); +          break; +        } + +        this->write_reg(clk_regs.output(clk_regs.tx_db)); +        this->update_regs(); +    } + +    void set_rate_tx_dboard_clock(double rate){ +        assert_has(get_rates_tx_dboard_clock(), rate, "tx dboard clock rate"); +        size_t divider = size_t(get_master_clock_rate()/rate); +        //bypass when the divider ratio is one +        _ad9510_regs.bypass_divider_out6 = (divider == 1)? 1 : 0; +        //calculate the low and high dividers +        size_t high = divider/2; +        size_t low = divider - high; + +        switch(clk_regs.tx_db) { +        case 5: //USRP2+ +          _ad9510_regs.bypass_divider_out5 = (divider == 1)? 1 : 0; +          _ad9510_regs.divider_low_cycles_out5 = low - 1; +          _ad9510_regs.divider_high_cycles_out5 = high - 1; +          break; +        case 6: //USRP2 +          //bypass when the divider ratio is one +          _ad9510_regs.bypass_divider_out6 = (divider == 1)? 1 : 0; +          //set the registers (divider - 1) +          _ad9510_regs.divider_low_cycles_out6 = low - 1; +          _ad9510_regs.divider_high_cycles_out6 = high - 1; +          break; +        } + +        //write the registers +        this->write_reg(clk_regs.div_hi(clk_regs.tx_db)); +        this->write_reg(clk_regs.div_lo(clk_regs.tx_db)); +        this->update_regs(); +    } + +    std::vector<double> get_rates_tx_dboard_clock(void){ +        return get_rates_rx_dboard_clock(); //same master clock, same dividers... +    } +     +    void enable_test_clock(bool enb) { +        _ad9510_regs.power_down_lvpecl_out0 = enb? +            ad9510_regs_t::POWER_DOWN_LVPECL_OUT0_NORMAL : +            ad9510_regs_t::POWER_DOWN_LVPECL_OUT0_SAFE_PD; +        _ad9510_regs.output_level_lvpecl_out0 = ad9510_regs_t::OUTPUT_LEVEL_LVPECL_OUT0_810MV; +        _ad9510_regs.divider_low_cycles_out0 = 0; +        _ad9510_regs.divider_high_cycles_out0 = 0; +        _ad9510_regs.bypass_divider_out0 = 1; +        this->write_reg(0x3c); +        this->write_reg(0x48); +        this->write_reg(0x49); +    } + +    /*! +     * If we are to use an external reference, enable the charge pump. +     * \param enb true to enable the CP +     */ +    void enable_external_ref(bool enb){ +        _ad9510_regs.charge_pump_mode = (enb)? +            ad9510_regs_t::CHARGE_PUMP_MODE_NORMAL : +            ad9510_regs_t::CHARGE_PUMP_MODE_3STATE ; +        _ad9510_regs.pll_mux_control = ad9510_regs_t::PLL_MUX_CONTROL_DLD_HIGH; +        _ad9510_regs.pfd_polarity = ad9510_regs_t::PFD_POLARITY_POS; +        this->write_reg(clk_regs.pll_2); +        this->update_regs(); +    } + +    double get_master_clock_rate(void){ +        return 100e6; +    } +     +    void set_mimo_clock_delay(double delay) { +        //delay_val is a 5-bit value (0-31) for fine control +        //the equations below determine delay for a given ramp current, # of caps and fine delay register +        //delay range: +        //range_ns = 200*((caps+3)/i_ramp_ua)*1.3286 +        //offset (zero delay): +        //offset_ns = 0.34 + (1600 - i_ramp_ua)*1e-4 + ((caps-1)/ramp)*6 +        //delay_ns = offset_ns + range_ns * delay / 31 + +        int delay_val = boost::math::iround(delay/9.744e-9*31); + +        if(delay_val == 0) { +            switch(clk_regs.exp) { +            case 5: +                _ad9510_regs.delay_control_out5 = 1; +                break; +            case 6: +                _ad9510_regs.delay_control_out6 = 1; +                break; +            default: +                break; //delay not supported on U2 rev 3 +            } +        } else { +            switch(clk_regs.exp) { +            case 5: +                _ad9510_regs.delay_control_out5 = 0; +                _ad9510_regs.ramp_current_out5 = ad9510_regs_t::RAMP_CURRENT_OUT5_200UA; +                _ad9510_regs.ramp_capacitor_out5 = ad9510_regs_t::RAMP_CAPACITOR_OUT5_4CAPS; +                _ad9510_regs.delay_fine_adjust_out5 = delay_val; +                this->write_reg(0x34); +                this->write_reg(0x35); +                this->write_reg(0x36); +                break; +            case 6: +                _ad9510_regs.delay_control_out6 = 0; +                _ad9510_regs.ramp_current_out6 = ad9510_regs_t::RAMP_CURRENT_OUT6_200UA; +                _ad9510_regs.ramp_capacitor_out6 = ad9510_regs_t::RAMP_CAPACITOR_OUT6_4CAPS; +                _ad9510_regs.delay_fine_adjust_out6 = delay_val; +                this->write_reg(0x38); +                this->write_reg(0x39); +                this->write_reg(0x3A); +                break; +            default: +                break; +            } +        } +    } + +private: +    /*! +     * Write a single register to the spi regs. +     * \param addr the address to write +     */ +    void write_reg(boost::uint8_t addr){ +        boost::uint32_t data = _ad9510_regs.get_write_reg(addr); +        _spiface->write_spi(SPI_SS_AD9510, spi_config_t::EDGE_RISE, data, 24); +    } + +    /*! +     * Tells the ad9510 to latch the settings into the operational registers. +     */ +    void update_regs(void){ +        _ad9510_regs.update_registers = 1; +        this->write_reg(clk_regs.update); +    } + +    //uses output clock 3 (pecl) +    //this is the same between USRP2 and USRP2+ and doesn't get a switch statement +    void enable_dac_clock(bool enb){ +        _ad9510_regs.power_down_lvpecl_out3 = (enb)? +            ad9510_regs_t::POWER_DOWN_LVPECL_OUT3_NORMAL : +            ad9510_regs_t::POWER_DOWN_LVPECL_OUT3_SAFE_PD; +        _ad9510_regs.output_level_lvpecl_out3 = ad9510_regs_t::OUTPUT_LEVEL_LVPECL_OUT3_810MV; +        _ad9510_regs.bypass_divider_out3 = 1; +        this->write_reg(clk_regs.output(clk_regs.dac)); +        this->write_reg(clk_regs.div_hi(clk_regs.dac)); +        this->update_regs(); +    } + +    //uses output clock 4 (lvds) on USRP2 and output clock 2 (lvpecl) on USRP2+ +    void enable_adc_clock(bool enb){ +        switch(clk_regs.adc) { +        case 2: +          _ad9510_regs.power_down_lvpecl_out2 = enb? ad9510_regs_t::POWER_DOWN_LVPECL_OUT2_NORMAL : ad9510_regs_t::POWER_DOWN_LVPECL_OUT2_SAFE_PD; +          _ad9510_regs.output_level_lvpecl_out2 = ad9510_regs_t::OUTPUT_LEVEL_LVPECL_OUT2_500MV; +          _ad9510_regs.bypass_divider_out2 = 1; +          break; +        case 4: +          _ad9510_regs.power_down_lvds_cmos_out4 = enb? 0 : 1; +          _ad9510_regs.lvds_cmos_select_out4 = ad9510_regs_t::LVDS_CMOS_SELECT_OUT4_LVDS; +          _ad9510_regs.output_level_lvds_out4 = ad9510_regs_t::OUTPUT_LEVEL_LVDS_OUT4_1_75MA; +          _ad9510_regs.bypass_divider_out4 = 1; +          break; +        } + +        this->write_reg(clk_regs.output(clk_regs.adc)); +        this->write_reg(clk_regs.div_hi(clk_regs.adc)); +        this->update_regs(); +    } +     +    usrp2_iface::sptr _iface; +    uhd::spi_iface::sptr _spiface; +    usrp2_clk_regs_t clk_regs; +    ad9510_regs_t _ad9510_regs; +}; + +/*********************************************************************** + * Public make function for the ad9510 clock control + **********************************************************************/ +usrp2_clock_ctrl::sptr usrp2_clock_ctrl::make(usrp2_iface::sptr iface, uhd::spi_iface::sptr spiface){ +    return sptr(new usrp2_clock_ctrl_impl(iface, spiface)); +} diff --git a/host/lib/usrp/usrp2/clock_ctrl.hpp b/host/lib/usrp/usrp2/clock_ctrl.hpp new file mode 100644 index 000000000..067e1e35d --- /dev/null +++ b/host/lib/usrp/usrp2/clock_ctrl.hpp @@ -0,0 +1,110 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_CLOCK_CTRL_HPP +#define INCLUDED_CLOCK_CTRL_HPP + +#include "usrp2_iface.hpp" +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> +#include <vector> + +class usrp2_clock_ctrl : boost::noncopyable{ +public: +    typedef boost::shared_ptr<usrp2_clock_ctrl> sptr; + +    /*! +     * Make a clock config for the ad9510 ic. +     * \param iface a pointer to the usrp2 interface object +     * \param spiface the interface to spi +     * \return a new clock control object +     */ +    static sptr make(usrp2_iface::sptr iface, uhd::spi_iface::sptr spiface); + +    /*! +     * Get the master clock frequency for the fpga. +     * \return the clock frequency in Hz +     */ +    virtual double get_master_clock_rate(void) = 0; + +    /*! +     * Enable/disable the rx dboard clock. +     * \param enb true to enable +     */ +    virtual void enable_rx_dboard_clock(bool enb) = 0; + +    /*! +     * Set the clock rate on the rx dboard clock. +     * \param rate the new clock rate +     * \throw exception when rate invalid +     */ +    virtual void set_rate_rx_dboard_clock(double rate) = 0; + +    /*! +     * Get a list of possible rx dboard clock rates. +     * \return a list of clock rates in Hz +     */ +    virtual std::vector<double> get_rates_rx_dboard_clock(void) = 0; + +    /*! +     * Enable/disable the tx dboard clock. +     * \param enb true to enable +     */ +    virtual void enable_tx_dboard_clock(bool enb) = 0; + +    /*! +     * Set the clock rate on the tx dboard clock. +     * \param rate the new clock rate +     * \throw exception when rate invalid +     */ +    virtual void set_rate_tx_dboard_clock(double rate) = 0; + +    /*! +     * Get a list of possible tx dboard clock rates. +     * \return a list of clock rates in Hz +     */ +    virtual std::vector<double> get_rates_tx_dboard_clock(void) = 0; + +    /*! +     * Enable/disable external reference. +     * \param enb true to enable +     */ +    virtual void enable_external_ref(bool enb) = 0; +     +    /*! +     * Enable/disable test clock output. +     * \param enb true to enable +     */ +    virtual void enable_test_clock(bool enb) = 0; + +    /*! +     * Enable/disable the ref clock output over the serdes cable. +     * \param enb true to enable +     */ +    virtual void enable_mimo_clock_out(bool enb) = 0; +     +    /*! +     * Set the output delay of the mimo clock +     * Used to synchronise daisy-chained USRPs over the MIMO cable +     * Can also be used to adjust delay for uneven reference cable lengths +     * \param delay the clock delay in seconds +     */ +    virtual void set_mimo_clock_delay(double delay) = 0; + +}; + +#endif /* INCLUDED_CLOCK_CTRL_HPP */ diff --git a/host/lib/usrp/usrp2/codec_ctrl.cpp b/host/lib/usrp/usrp2/codec_ctrl.cpp new file mode 100644 index 000000000..b53c4d9df --- /dev/null +++ b/host/lib/usrp/usrp2/codec_ctrl.cpp @@ -0,0 +1,218 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "codec_ctrl.hpp" +#include "ad9777_regs.hpp" +#include "ads62p44_regs.hpp" +#include "usrp2_regs.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/utils/safe_call.hpp> +#include <uhd/exception.hpp> +#include <boost/cstdint.hpp> +#include <boost/foreach.hpp> + +using namespace uhd; + +/*! + * A usrp2 codec control specific to the ad9777 ic. + */ +class usrp2_codec_ctrl_impl : public usrp2_codec_ctrl{ +public: +    usrp2_codec_ctrl_impl(usrp2_iface::sptr iface, uhd::spi_iface::sptr spiface){ +        _iface = iface; +        _spiface = spiface; + +        //setup the ad9777 dac +        _ad9777_regs.x_1r_2r_mode = ad9777_regs_t::X_1R_2R_MODE_1R; +        _ad9777_regs.filter_interp_rate = ad9777_regs_t::FILTER_INTERP_RATE_4X; +        _ad9777_regs.mix_mode = ad9777_regs_t::MIX_MODE_COMPLEX; +        _ad9777_regs.pll_divide_ratio = ad9777_regs_t::PLL_DIVIDE_RATIO_DIV1; +        _ad9777_regs.pll_state = ad9777_regs_t::PLL_STATE_ON; +        _ad9777_regs.auto_cp_control = ad9777_regs_t::AUTO_CP_CONTROL_AUTO; +        //I dac values +        _ad9777_regs.idac_fine_gain_adjust = 0; +        _ad9777_regs.idac_coarse_gain_adjust = 0xf; +        _ad9777_regs.idac_offset_adjust_lsb = 0; +        _ad9777_regs.idac_offset_adjust_msb = 0; +        //Q dac values +        _ad9777_regs.qdac_fine_gain_adjust = 0; +        _ad9777_regs.qdac_coarse_gain_adjust = 0xf; +        _ad9777_regs.qdac_offset_adjust_lsb = 0; +        _ad9777_regs.qdac_offset_adjust_msb = 0; +        //write all regs +        for(boost::uint8_t addr = 0; addr <= 0xC; addr++){ +            this->send_ad9777_reg(addr); +        } +        set_tx_mod_mode(0); + +        //power-up adc +        switch(_iface->get_rev()){ +        case usrp2_iface::USRP2_REV3: +        case usrp2_iface::USRP2_REV4: +            _iface->poke32(U2_REG_MISC_CTRL_ADC, U2_FLAG_MISC_CTRL_ADC_ON); +            break; + +        case usrp2_iface::USRP_N200: +        case usrp2_iface::USRP_N210: +            _ads62p44_regs.reset = 1; +            this->send_ads62p44_reg(0x00); //issue a reset to the ADC +            //everything else should be pretty much default, i think +            //_ads62p44_regs.decimation = DECIMATION_DECIMATE_1; +            _ads62p44_regs.power_down = ads62p44_regs_t::POWER_DOWN_NORMAL; +            this->send_ads62p44_reg(0x14); +            this->set_rx_analog_gain(1); +            break; + +        case usrp2_iface::USRP_N200_R4: +        case usrp2_iface::USRP_N210_R4: +            _ads62p44_regs.reset = 1; +            this->send_ads62p44_reg(0x00); //issue a reset to the ADC +            //everything else should be pretty much default, i think +            //_ads62p44_regs.decimation = DECIMATION_DECIMATE_1; +            _ads62p44_regs.override = 1; +            this->send_ads62p44_reg(0x14); +            _ads62p44_regs.power_down = ads62p44_regs_t::POWER_DOWN_NORMAL; +            _ads62p44_regs.output_interface = ads62p44_regs_t::OUTPUT_INTERFACE_LVDS; +            _ads62p44_regs.lvds_current = ads62p44_regs_t::LVDS_CURRENT_2_5MA; +            _ads62p44_regs.lvds_data_term = ads62p44_regs_t::LVDS_DATA_TERM_100; +            this->send_ads62p44_reg(0x11); +            this->send_ads62p44_reg(0x12); +            this->send_ads62p44_reg(0x14); +            this->set_rx_analog_gain(1); +            break; + +        case usrp2_iface::USRP_NXXX: break; +        } +    } + +    ~usrp2_codec_ctrl_impl(void){UHD_SAFE_CALL( +        //power-down dac +        _ad9777_regs.power_down_mode = 1; +        this->send_ad9777_reg(0); + +        //power-down adc +        switch(_iface->get_rev()){ +        case usrp2_iface::USRP2_REV3: +        case usrp2_iface::USRP2_REV4: +            _iface->poke32(U2_REG_MISC_CTRL_ADC, U2_FLAG_MISC_CTRL_ADC_OFF); +            break; + +        case usrp2_iface::USRP_N200: +        case usrp2_iface::USRP_N210: +        case usrp2_iface::USRP_N200_R4: +        case usrp2_iface::USRP_N210_R4: +            //send a global power-down to the ADC here... it will get lifted on reset +            _ads62p44_regs.power_down = ads62p44_regs_t::POWER_DOWN_GLOBAL_PD; +            this->send_ads62p44_reg(0x14); +            break; + +        case usrp2_iface::USRP_NXXX: break; +        } +    )} + +    void set_tx_mod_mode(int mod_mode){ +        //set the sign of the frequency shift +        _ad9777_regs.modulation_form = (mod_mode > 0)? +            ad9777_regs_t::MODULATION_FORM_E_PLUS_JWT: +            ad9777_regs_t::MODULATION_FORM_E_MINUS_JWT +        ; + +        //set the frequency shift +        switch(std::abs(mod_mode)){ +        case 0: +        case 1: _ad9777_regs.modulation_mode = ad9777_regs_t::MODULATION_MODE_NONE; break; +        case 2: _ad9777_regs.modulation_mode = ad9777_regs_t::MODULATION_MODE_FS_2; break; +        case 4: _ad9777_regs.modulation_mode = ad9777_regs_t::MODULATION_MODE_FS_4; break; +        case 8: _ad9777_regs.modulation_mode = ad9777_regs_t::MODULATION_MODE_FS_8; break; +        default: throw uhd::value_error("unknown modulation mode for ad9777"); +        } + +        this->send_ad9777_reg(0x01); //set the register +    } + +    void set_rx_digital_gain(double gain) {  //fine digital gain +        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: +            _ads62p44_regs.fine_gain = int(gain/0.5); +            this->send_ads62p44_reg(0x17); +            break; + +        default: UHD_THROW_INVALID_CODE_PATH(); +        } +    } + +    void set_rx_digital_fine_gain(double gain) { //gain correction       +        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: +            _ads62p44_regs.gain_correction = int(gain / 0.05); +            this->send_ads62p44_reg(0x1A); +            break; + +        default: UHD_THROW_INVALID_CODE_PATH(); +        } +    } + +    void set_rx_analog_gain(bool /*gain*/) { //turns on/off analog 3.5dB preamp +        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: +            _ads62p44_regs.coarse_gain = ads62p44_regs_t::COARSE_GAIN_3_5DB;//gain ? ads62p44_regs_t::COARSE_GAIN_3_5DB : ads62p44_regs_t::COARSE_GAIN_0DB; +            this->send_ads62p44_reg(0x14); +            break; + +        default: UHD_THROW_INVALID_CODE_PATH(); +        } +    } + +private: +    ad9777_regs_t _ad9777_regs; +    ads62p44_regs_t _ads62p44_regs; +    usrp2_iface::sptr _iface; +    uhd::spi_iface::sptr _spiface; + +    void send_ad9777_reg(boost::uint8_t addr){ +        boost::uint16_t reg = _ad9777_regs.get_write_reg(addr); +        UHD_LOGV(always) << "send_ad9777_reg: " << std::hex << reg << std::endl; +        _spiface->write_spi( +            SPI_SS_AD9777, spi_config_t::EDGE_RISE, +            reg, 16 +        ); +    } + +    void send_ads62p44_reg(boost::uint8_t addr) { +        boost::uint16_t reg = _ads62p44_regs.get_write_reg(addr); +        _spiface->write_spi( +            SPI_SS_ADS62P44, spi_config_t::EDGE_FALL, +            reg, 16 +        ); +    } +}; + +/*********************************************************************** + * Public make function for the usrp2 codec control + **********************************************************************/ +usrp2_codec_ctrl::sptr usrp2_codec_ctrl::make(usrp2_iface::sptr iface, uhd::spi_iface::sptr spiface){ +    return sptr(new usrp2_codec_ctrl_impl(iface, spiface)); +} diff --git a/host/lib/usrp/usrp2/codec_ctrl.hpp b/host/lib/usrp/usrp2/codec_ctrl.hpp new file mode 100644 index 000000000..b0d815be2 --- /dev/null +++ b/host/lib/usrp/usrp2/codec_ctrl.hpp @@ -0,0 +1,69 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_CODEC_CTRL_HPP +#define INCLUDED_CODEC_CTRL_HPP + +#include "usrp2_iface.hpp" +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> + +class usrp2_codec_ctrl : boost::noncopyable{ +public: +    typedef boost::shared_ptr<usrp2_codec_ctrl> sptr; + +    /*! +     * Make a codec control for the DAC and ADC. +     * \param iface a pointer to the usrp2 interface object +     * \param spiface the interface to spi +     * \return a new codec control object +     */ +    static sptr make(usrp2_iface::sptr iface, uhd::spi_iface::sptr spiface); + +    /*! +     * Set the modulation mode for the DAC. +     * Possible modes are 0, +/-1, +/-2, +/-4, +/-8 +     * which correspond to shifts of fs/mod_mode. +     * A mode of 0 or +/-1 means no modulation. +     * \param mod_mode the modulation mode +     */ +    virtual void set_tx_mod_mode(int mod_mode) = 0; + +    /*! +     * Set the analog preamplifier on the USRP2+ ADC (ADS62P44). +     * \param gain enable or disable the 3.5dB preamp +     */ + +    virtual void set_rx_analog_gain(bool gain) = 0; + +    /*! +     * Set the digital gain on the USRP2+ ADC (ADS62P44). +     * \param gain from 0-6dB +     */ + +    virtual void set_rx_digital_gain(double gain) = 0; + +    /*! +     * Set the digital gain correction on the USRP2+ ADC (ADS62P44). +     * \param gain from 0-0.5dB +     */ + +    virtual void set_rx_digital_fine_gain(double gain) = 0; + +}; + +#endif /* INCLUDED_CODEC_CTRL_HPP */ diff --git a/host/lib/usrp/usrp2/dboard_iface.cpp b/host/lib/usrp/usrp2/dboard_iface.cpp new file mode 100644 index 000000000..edd9ef242 --- /dev/null +++ b/host/lib/usrp/usrp2/dboard_iface.cpp @@ -0,0 +1,307 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "gpio_core_200.hpp" +#include <uhd/types/serial.hpp> +#include "clock_ctrl.hpp" +#include "usrp2_regs.hpp" //wishbone address constants +#include <uhd/usrp/dboard_iface.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/algorithm.hpp> +#include <boost/assign/list_of.hpp> +#include <boost/asio.hpp> //htonl and ntohl +#include <boost/math/special_functions/round.hpp> +#include "ad7922_regs.hpp" //aux adc +#include "ad5623_regs.hpp" //aux dac + +using namespace uhd; +using namespace uhd::usrp; +using namespace boost::assign; + +class usrp2_dboard_iface : public dboard_iface{ +public: +    usrp2_dboard_iface( +        wb_iface::sptr wb_iface, +        uhd::i2c_iface::sptr i2c_iface, +        uhd::spi_iface::sptr spi_iface, +        usrp2_clock_ctrl::sptr clock_ctrl +    ); +    ~usrp2_dboard_iface(void); + +    special_props_t get_special_props(void){ +        special_props_t props; +        props.soft_clock_divider = false; +        props.mangle_i2c_addrs = false; +        return props; +    } + +    void write_aux_dac(unit_t, aux_dac_t, double); +    double read_aux_adc(unit_t, aux_adc_t); + +    void _set_pin_ctrl(unit_t, boost::uint16_t); +    void _set_atr_reg(unit_t, atr_reg_t, boost::uint16_t); +    void _set_gpio_ddr(unit_t, boost::uint16_t); +    void _set_gpio_out(unit_t, boost::uint16_t); +    void set_gpio_debug(unit_t, int); +    boost::uint16_t read_gpio(unit_t); + +    void write_i2c(boost::uint8_t, const byte_vector_t &); +    byte_vector_t read_i2c(boost::uint8_t, size_t); + +    void set_clock_rate(unit_t, double); +    double get_clock_rate(unit_t); +    std::vector<double> get_clock_rates(unit_t); +    void set_clock_enabled(unit_t, bool); +    double get_codec_rate(unit_t); + +    void write_spi( +        unit_t unit, +        const spi_config_t &config, +        boost::uint32_t data, +        size_t num_bits +    ); + +    boost::uint32_t read_write_spi( +        unit_t unit, +        const spi_config_t &config, +        boost::uint32_t data, +        size_t num_bits +    ); + +private: +    uhd::i2c_iface::sptr _i2c_iface; +    uhd::spi_iface::sptr _spi_iface; +    usrp2_clock_ctrl::sptr _clock_ctrl; +    gpio_core_200::sptr _gpio; + +    uhd::dict<unit_t, ad5623_regs_t> _dac_regs; +    uhd::dict<unit_t, double> _clock_rates; +    void _write_aux_dac(unit_t); +}; + +/*********************************************************************** + * Make Function + **********************************************************************/ +dboard_iface::sptr make_usrp2_dboard_iface( +    wb_iface::sptr wb_iface, +    uhd::i2c_iface::sptr i2c_iface, +    uhd::spi_iface::sptr spi_iface, +    usrp2_clock_ctrl::sptr clock_ctrl +){ +    return dboard_iface::sptr(new usrp2_dboard_iface(wb_iface, i2c_iface, spi_iface, clock_ctrl)); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +usrp2_dboard_iface::usrp2_dboard_iface( +    wb_iface::sptr wb_iface, +    uhd::i2c_iface::sptr i2c_iface, +    uhd::spi_iface::sptr spi_iface, +    usrp2_clock_ctrl::sptr clock_ctrl +): +    _i2c_iface(i2c_iface), +    _spi_iface(spi_iface), +    _clock_ctrl(clock_ctrl) +{ +    _gpio = gpio_core_200::make(wb_iface, U2_REG_SR_ADDR(SR_GPIO), U2_REG_GPIO_RB); + +    //reset the aux dacs +    _dac_regs[UNIT_RX] = ad5623_regs_t(); +    _dac_regs[UNIT_TX] = ad5623_regs_t(); +    BOOST_FOREACH(unit_t unit, _dac_regs.keys()){ +        _dac_regs[unit].data = 1; +        _dac_regs[unit].addr = ad5623_regs_t::ADDR_ALL; +        _dac_regs[unit].cmd  = ad5623_regs_t::CMD_RESET; +        this->_write_aux_dac(unit); +    } + +    //init the clock rate shadows with max rate clock +    this->set_clock_rate(UNIT_RX, sorted(this->get_clock_rates(UNIT_RX)).back()); +    this->set_clock_rate(UNIT_TX, sorted(this->get_clock_rates(UNIT_TX)).back()); +} + +usrp2_dboard_iface::~usrp2_dboard_iface(void){ +    /* NOP */ +} + +/*********************************************************************** + * Clocks + **********************************************************************/ +void usrp2_dboard_iface::set_clock_rate(unit_t unit, double rate){ +    _clock_rates[unit] = rate; //set to shadow +    switch(unit){ +    case UNIT_RX: _clock_ctrl->set_rate_rx_dboard_clock(rate); return; +    case UNIT_TX: _clock_ctrl->set_rate_tx_dboard_clock(rate); return; +    } +} + +double usrp2_dboard_iface::get_clock_rate(unit_t unit){ +    return _clock_rates[unit]; //get from shadow +} + +std::vector<double> usrp2_dboard_iface::get_clock_rates(unit_t unit){ +    switch(unit){ +    case UNIT_RX: return _clock_ctrl->get_rates_rx_dboard_clock(); +    case UNIT_TX: return _clock_ctrl->get_rates_tx_dboard_clock(); +    default: UHD_THROW_INVALID_CODE_PATH(); +    } +} + +void usrp2_dboard_iface::set_clock_enabled(unit_t unit, bool enb){ +    switch(unit){ +    case UNIT_RX: _clock_ctrl->enable_rx_dboard_clock(enb); return; +    case UNIT_TX: _clock_ctrl->enable_tx_dboard_clock(enb); return; +    } +} + +double usrp2_dboard_iface::get_codec_rate(unit_t){ +    return _clock_ctrl->get_master_clock_rate(); +} +/*********************************************************************** + * GPIO + **********************************************************************/ +void usrp2_dboard_iface::_set_pin_ctrl(unit_t unit, boost::uint16_t value){ +    return _gpio->set_pin_ctrl(unit, value); +} + +void usrp2_dboard_iface::_set_gpio_ddr(unit_t unit, boost::uint16_t value){ +    return _gpio->set_gpio_ddr(unit, value); +} + +void usrp2_dboard_iface::_set_gpio_out(unit_t unit, boost::uint16_t value){ +    return _gpio->set_gpio_out(unit, value); +} + +boost::uint16_t usrp2_dboard_iface::read_gpio(unit_t unit){ +    return _gpio->read_gpio(unit); +} + +void usrp2_dboard_iface::_set_atr_reg(unit_t unit, atr_reg_t atr, boost::uint16_t value){ +    return _gpio->set_atr_reg(unit, atr, value); +} + +void usrp2_dboard_iface::set_gpio_debug(unit_t, int){ +    throw uhd::not_implemented_error("no set_gpio_debug implemented"); +} + +/*********************************************************************** + * SPI + **********************************************************************/ +static const uhd::dict<dboard_iface::unit_t, int> unit_to_spi_dev = map_list_of +    (dboard_iface::UNIT_TX, SPI_SS_TX_DB) +    (dboard_iface::UNIT_RX, SPI_SS_RX_DB) +; + +void usrp2_dboard_iface::write_spi( +    unit_t unit, +    const spi_config_t &config, +    boost::uint32_t data, +    size_t num_bits +){ +    _spi_iface->write_spi(unit_to_spi_dev[unit], config, data, num_bits); +} + +boost::uint32_t usrp2_dboard_iface::read_write_spi( +    unit_t unit, +    const spi_config_t &config, +    boost::uint32_t data, +    size_t num_bits +){ +    return _spi_iface->read_spi(unit_to_spi_dev[unit], config, data, num_bits); +} + +/*********************************************************************** + * I2C + **********************************************************************/ +void usrp2_dboard_iface::write_i2c(boost::uint8_t addr, const byte_vector_t &bytes){ +    return _i2c_iface->write_i2c(addr, bytes); +} + +byte_vector_t usrp2_dboard_iface::read_i2c(boost::uint8_t addr, size_t num_bytes){ +    return _i2c_iface->read_i2c(addr, num_bytes); +} + +/*********************************************************************** + * Aux DAX/ADC + **********************************************************************/ +void usrp2_dboard_iface::_write_aux_dac(unit_t unit){ +    static const uhd::dict<unit_t, int> unit_to_spi_dac = map_list_of +        (UNIT_RX, SPI_SS_RX_DAC) +        (UNIT_TX, SPI_SS_TX_DAC) +    ; +    _spi_iface->write_spi( +        unit_to_spi_dac[unit], spi_config_t::EDGE_FALL,  +        _dac_regs[unit].get_reg(), 24 +    ); +} + +void usrp2_dboard_iface::write_aux_dac(unit_t unit, aux_dac_t which, double value){ +    _dac_regs[unit].data = boost::math::iround(4095*value/3.3); +    _dac_regs[unit].cmd = ad5623_regs_t::CMD_WR_UP_DAC_CHAN_N; + +    typedef uhd::dict<aux_dac_t, ad5623_regs_t::addr_t> aux_dac_to_addr; +    static const uhd::dict<unit_t, aux_dac_to_addr> unit_to_which_to_addr = map_list_of +        (UNIT_RX, map_list_of +            (AUX_DAC_A, ad5623_regs_t::ADDR_DAC_B) +            (AUX_DAC_B, ad5623_regs_t::ADDR_DAC_A) +            (AUX_DAC_C, ad5623_regs_t::ADDR_DAC_A) +            (AUX_DAC_D, ad5623_regs_t::ADDR_DAC_B) +        ) +        (UNIT_TX, map_list_of +            (AUX_DAC_A, ad5623_regs_t::ADDR_DAC_A) +            (AUX_DAC_B, ad5623_regs_t::ADDR_DAC_B) +            (AUX_DAC_C, ad5623_regs_t::ADDR_DAC_B) +            (AUX_DAC_D, ad5623_regs_t::ADDR_DAC_A) +        ) +    ; +    _dac_regs[unit].addr = unit_to_which_to_addr[unit][which]; +    this->_write_aux_dac(unit); +} + +double usrp2_dboard_iface::read_aux_adc(unit_t unit, aux_adc_t which){ +    static const uhd::dict<unit_t, int> unit_to_spi_adc = map_list_of +        (UNIT_RX, SPI_SS_RX_ADC) +        (UNIT_TX, SPI_SS_TX_ADC) +    ; + +    //setup spi config args +    spi_config_t config; +    config.mosi_edge = spi_config_t::EDGE_FALL; +    config.miso_edge = spi_config_t::EDGE_RISE; + +    //setup the spi registers +    ad7922_regs_t ad7922_regs; +    switch(which){ +    case AUX_ADC_A: ad7922_regs.mod = 0; break; +    case AUX_ADC_B: ad7922_regs.mod = 1; break; +    } ad7922_regs.chn = ad7922_regs.mod; //normal mode: mod == chn + +    //write and read spi +    _spi_iface->write_spi( +        unit_to_spi_adc[unit], config, +        ad7922_regs.get_reg(), 16 +    ); +    ad7922_regs.set_reg(boost::uint16_t(_spi_iface->read_spi( +        unit_to_spi_adc[unit], config, +        ad7922_regs.get_reg(), 16 +    ))); + +    //convert to voltage and return +    return 3.3*ad7922_regs.result/4095; +} diff --git a/host/lib/usrp/usrp2/fw_common.h b/host/lib/usrp/usrp2/fw_common.h new file mode 100644 index 000000000..7e3de1497 --- /dev/null +++ b/host/lib/usrp/usrp2/fw_common.h @@ -0,0 +1,162 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_USRP2_FW_COMMON_H +#define INCLUDED_USRP2_FW_COMMON_H + +#include <stdint.h> + +/*! + * Structs and constants for usrp2 communication. + * This header is shared by the firmware and host code. + * Therefore, this header may only contain valid C code. + */ +#ifdef __cplusplus +extern "C" { +#endif + +//fpga and firmware compatibility numbers +#define USRP2_FPGA_COMPAT_NUM 10 +#define USRP2_FW_COMPAT_NUM 12 +#define USRP2_FW_VER_MINOR 3 + +//used to differentiate control packets over data port +#define USRP2_INVALID_VRT_HEADER 0 + +typedef struct{ +    uint32_t sequence; +    uint32_t vrt_hdr; +    uint32_t ip_addr; +    uint32_t udp_port; +} usrp2_stream_ctrl_t; + +// udp ports for the usrp2 communication +// Dynamic and/or private ports: 49152-65535 +#define USRP2_UDP_CTRL_PORT 49152 +//#define USRP2_UDP_UPDATE_PORT 49154 +#define USRP2_UDP_RX_DSP0_PORT 49156 +#define USRP2_UDP_TX_DSP0_PORT 49157 +#define USRP2_UDP_RX_DSP1_PORT 49158 +#define USRP2_UDP_FIFO_CRTL_PORT 49159 +#define USRP2_UDP_UART_BASE_PORT 49170 +#define USRP2_UDP_UART_GPS_PORT 49172 + +// Map for virtual firmware regs (not very big so we can keep it here for now) +#define U2_FW_REG_LOCK_TIME 0 +#define U2_FW_REG_LOCK_GPID 1 +#define U2_FW_REG_HAS_GPSDO 3 +#define U2_FW_REG_VER_MINOR 7 + +//////////////////////////////////////////////////////////////////////// +// I2C addresses +//////////////////////////////////////////////////////////////////////// +#define USRP2_I2C_DEV_EEPROM  0x50 // 24LC02[45]:  7-bits 1010xxx +#define	USRP2_I2C_ADDR_MBOARD (USRP2_I2C_DEV_EEPROM | 0x0) +#define	USRP2_I2C_ADDR_TX_DB  (USRP2_I2C_DEV_EEPROM | 0x4) +#define	USRP2_I2C_ADDR_RX_DB  (USRP2_I2C_DEV_EEPROM | 0x5) + +//////////////////////////////////////////////////////////////////////// +// EEPROM Layout +//////////////////////////////////////////////////////////////////////// +#define USRP2_EE_MBOARD_REV      0x00 //2 bytes, little-endian (historic, don't blame me) +#define USRP2_EE_MBOARD_MAC_ADDR 0x02 //6 bytes +#define USRP2_EE_MBOARD_GATEWAY  0x38 //uint32, big-endian +#define USRP2_EE_MBOARD_SUBNET   0x08 //uint32, big-endian +#define USRP2_EE_MBOARD_IP_ADDR  0x0C //uint32, big-endian +#define USRP2_EE_MBOARD_BOOTLOADER_FLAGS 0xF7 + +typedef enum{ +    USRP2_CTRL_ID_HUH_WHAT = ' ', +    //USRP2_CTRL_ID_FOR_SURE, //TODO error condition enums +    //USRP2_CTRL_ID_SUX_MAN, + +    USRP2_CTRL_ID_WAZZUP_BRO = 'a', +    USRP2_CTRL_ID_WAZZUP_DUDE = 'A', + +    USRP2_CTRL_ID_TRANSACT_ME_SOME_SPI_BRO = 's', +    USRP2_CTRL_ID_OMG_TRANSACTED_SPI_DUDE = 'S', + +    USRP2_CTRL_ID_DO_AN_I2C_READ_FOR_ME_BRO = 'i', +    USRP2_CTRL_ID_HERES_THE_I2C_DATA_DUDE = 'I', + +    USRP2_CTRL_ID_WRITE_THESE_I2C_VALUES_BRO = 'h', +    USRP2_CTRL_ID_COOL_IM_DONE_I2C_WRITE_DUDE = 'H', + +    USRP2_CTRL_ID_GET_THIS_REGISTER_FOR_ME_BRO = 'r', +    USRP2_CTRL_ID_OMG_GOT_REGISTER_SO_BAD_DUDE = 'R', + +    USRP2_CTRL_ID_HOLLER_AT_ME_BRO = 'l', +    USRP2_CTRL_ID_HOLLER_BACK_DUDE = 'L', + +    USRP2_CTRL_ID_PEACE_OUT = '~' + +} usrp2_ctrl_id_t; + +typedef enum{ +    USRP2_DIR_RX = 'r', +    USRP2_DIR_TX = 't' +} usrp2_dir_which_t; + +typedef enum{ +    USRP2_CLK_EDGE_RISE = 'r', +    USRP2_CLK_EDGE_FALL = 'f' +} usrp2_clk_edge_t; + +typedef enum{ +    USRP2_REG_ACTION_FPGA_PEEK32 = 1, +    USRP2_REG_ACTION_FPGA_PEEK16 = 2, +    USRP2_REG_ACTION_FPGA_POKE32 = 3, +    USRP2_REG_ACTION_FPGA_POKE16 = 4, +    USRP2_REG_ACTION_FW_PEEK32   = 5, +    USRP2_REG_ACTION_FW_POKE32   = 6 +} usrp2_reg_action_t; + +typedef struct{ +    uint32_t proto_ver; +    uint32_t id; +    uint32_t seq; +    union{ +        uint32_t ip_addr; +        struct { +            uint32_t dev; +            uint32_t data; +            uint8_t miso_edge; +            uint8_t mosi_edge; +            uint8_t num_bits; +            uint8_t readback; +        } spi_args; +        struct { +            uint8_t addr; +            uint8_t bytes; +            uint8_t data[20]; +        } i2c_args; +        struct { +            uint32_t addr; +            uint32_t data; +            uint8_t action; +        } reg_args; +        struct { +            uint32_t len; +        } echo_args; +    } data; +} usrp2_ctrl_data_t; + +#ifdef __cplusplus +} +#endif + +#endif /* INCLUDED_USRP2_FW_COMMON_H */ diff --git a/host/lib/usrp/usrp2/io_impl.cpp b/host/lib/usrp/usrp2/io_impl.cpp new file mode 100644 index 000000000..ea4aa716c --- /dev/null +++ b/host/lib/usrp/usrp2/io_impl.cpp @@ -0,0 +1,549 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "validate_subdev_spec.hpp" +#include "async_packet_handler.hpp" +#include "../../transport/super_recv_packet_handler.hpp" +#include "../../transport/super_send_packet_handler.hpp" +#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/tasks.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/byteswap.hpp> +#include <uhd/utils/thread_priority.hpp> +#include <uhd/transport/bounded_buffer.hpp> +#include <boost/thread/thread.hpp> +#include <boost/format.hpp> +#include <boost/bind.hpp> +#include <boost/asio.hpp> +#include <boost/thread/mutex.hpp> +#include <boost/make_shared.hpp> +#include <iostream> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; +namespace asio = boost::asio; +namespace pt = boost::posix_time; + +/*********************************************************************** + * helpers + **********************************************************************/ +static UHD_INLINE pt::time_duration to_time_dur(double timeout){ +    return pt::microseconds(long(timeout*1e6)); +} + +static UHD_INLINE double from_time_dur(const pt::time_duration &time_dur){ +    return 1e-6*time_dur.total_microseconds(); +} + +/*********************************************************************** + * constants + **********************************************************************/ +static const size_t vrt_send_header_offset_words32 = 1; + +/*********************************************************************** + * flow control monitor for a single tx channel + *  - the pirate thread calls update + *  - the get send buffer calls check + **********************************************************************/ +class flow_control_monitor{ +public: +    typedef boost::uint32_t seq_type; +    typedef boost::shared_ptr<flow_control_monitor> sptr; + +    /*! +     * Make a new flow control monitor. +     * \param max_seqs_out num seqs before throttling +     */ +    flow_control_monitor(seq_type max_seqs_out):_max_seqs_out(max_seqs_out){ +        this->clear(); +        _ready_fcn = boost::bind(&flow_control_monitor::ready, this); +    } + +    //! Clear the monitor, Ex: when a streamer is created +    void clear(void){ +        _last_seq_out = 0; +        _last_seq_ack = 0; +    } + +    /*! +     * Gets the current sequence number to go out. +     * Increments the sequence for the next call +     * \return the sequence to be sent to the dsp +     */ +    UHD_INLINE seq_type get_curr_seq_out(void){ +        return _last_seq_out++; +    } + +    /*! +     * Check the flow control condition. +     * \param timeout the timeout in seconds +     * \return false on timeout +     */ +    UHD_INLINE bool check_fc_condition(double timeout){ +        boost::mutex::scoped_lock lock(_fc_mutex); +        if (this->ready()) return true; +        boost::this_thread::disable_interruption di; //disable because the wait can throw +        return _fc_cond.timed_wait(lock, to_time_dur(timeout), _ready_fcn); +    } + +    /*! +     * Update the flow control condition. +     * \param seq the last sequence number to be ACK'd +     */ +    UHD_INLINE void update_fc_condition(seq_type seq){ +        boost::mutex::scoped_lock lock(_fc_mutex); +        _last_seq_ack = seq; +        lock.unlock(); +        _fc_cond.notify_one(); +    } + +private: +    bool ready(void){ +        return seq_type(_last_seq_out -_last_seq_ack) < _max_seqs_out; +    } + +    boost::mutex _fc_mutex; +    boost::condition _fc_cond; +    seq_type _last_seq_out, _last_seq_ack; +    const seq_type _max_seqs_out; +    boost::function<bool(void)> _ready_fcn; +}; + +/*********************************************************************** + * io impl details (internal to this file) + * - pirate crew + * - alignment buffer + * - thread loop + * - vrt packet handler states + **********************************************************************/ +struct usrp2_impl::io_impl{ + +    io_impl(void): +        async_msg_fifo(1000/*messages deep*/), +        tick_rate(1 /*non-zero default*/) +    { +        /* NOP */ +    } + +    ~io_impl(void){ +        //Manually deconstuct the tasks, since this was not happening automatically. +        pirate_tasks.clear(); +    } + +    managed_send_buffer::sptr get_send_buff(size_t chan, double timeout){ +        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 = 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()); + +        return buff; +    } + +    //tx dsp: xports and flow control monitors +    std::vector<zero_copy_if::sptr> tx_xports; +    std::vector<flow_control_monitor::sptr> fc_mons; + +    //methods and variables for the pirate crew +    void recv_pirate_loop(zero_copy_if::sptr, size_t); +    std::list<task::sptr> pirate_tasks; +    bounded_buffer<async_metadata_t> async_msg_fifo; +    double tick_rate; +}; + +/*********************************************************************** + * Receive Pirate Loop + * - while raiding, loot for message packet + * - update flow control condition count + * - put async message packets into queue + **********************************************************************/ +void usrp2_impl::io_impl::recv_pirate_loop( +    zero_copy_if::sptr err_xport, size_t index +){ +    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]); + +    while (not boost::this_thread::interruption_requested()){ +        managed_recv_buffer::sptr buff = err_xport->get_recv_buff(); +        if (not buff.get()) continue; //ignore timeout/error buffers + +        try{ +            //extract the vrt header packet info +            vrt::if_packet_info_t if_packet_info; +            if_packet_info.num_packet_words32 = buff->size()/sizeof(boost::uint32_t); +            const boost::uint32_t *vrt_hdr = buff->cast<const boost::uint32_t *>(); +            vrt::if_hdr_unpack_be(vrt_hdr, if_packet_info); + +            //handle a tx async report message +            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; +                load_metadata_from_buff(uhd::ntohx<boost::uint32_t>, metadata, if_packet_info, vrt_hdr, tick_rate, index); + +                //catch the flow control packets and react +                if (metadata.event_code == 0){ +                    boost::uint32_t fc_word32 = (vrt_hdr + if_packet_info.num_header_words32)[1]; +                    fc_mon.update_fc_condition(uhd::ntohx(fc_word32)); +                    continue; +                } +                //else UHD_MSG(often) << "metadata.event_code " << metadata.event_code << std::endl; +                async_msg_fifo.push_with_pop_on_full(metadata); + +                standard_async_msg_prints(metadata); +            } +            else{ +                //TODO unknown received packet, may want to print error... +            } +        }catch(const std::exception &e){ +            UHD_MSG(error) << "Error in recv pirate loop: " << e.what() << std::endl; +        } +    } +} + +/*********************************************************************** + * Helper Functions + **********************************************************************/ +void usrp2_impl::io_init(void){ +    //create new io impl +    _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].tx_dsp_xport); +        _io_impl->fc_mons.push_back(flow_control_monitor::sptr(new flow_control_monitor( +            USRP2_SRAM_BYTES/_mbc[mb].tx_dsp_xport->get_send_frame_size() +        ))); +    } + +    //allocate streamer weak ptrs containers +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        _mbc[mb].rx_streamers.resize(_mbc[mb].rx_dsps.size()); +        _mbc[mb].tx_streamers.resize(1/*known to be 1 dsp*/); +    } + +    //create a new pirate thread for each zc if (yarr!!) +    size_t index = 0; +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        //spawn a new pirate to plunder the recv booty +        _io_impl->pirate_tasks.push_back(task::make(boost::bind( +            &usrp2_impl::io_impl::recv_pirate_loop, _io_impl.get(), +            _mbc[mb].tx_dsp_xport, index++ +        ))); +    } +} + +void usrp2_impl::update_tick_rate(const double rate){ +    _io_impl->tick_rate = rate; //shadow for async msg + +    //update the tick rate on all existing streamers -> thread safe +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        for (size_t i = 0; i < _mbc[mb].rx_streamers.size(); i++){ +            boost::shared_ptr<sph::recv_packet_streamer> my_streamer = +                boost::dynamic_pointer_cast<sph::recv_packet_streamer>(_mbc[mb].rx_streamers[i].lock()); +            if (my_streamer.get() == NULL) continue; +            my_streamer->set_tick_rate(rate); +        } +        for (size_t i = 0; i < _mbc[mb].tx_streamers.size(); i++){ +            boost::shared_ptr<sph::send_packet_streamer> my_streamer = +                boost::dynamic_pointer_cast<sph::send_packet_streamer>(_mbc[mb].tx_streamers[i].lock()); +            if (my_streamer.get() == NULL) continue; +            my_streamer->set_tick_rate(rate); +        } +    } +} + +void usrp2_impl::update_rx_samp_rate(const std::string &mb, const size_t dsp, const double rate){ +    boost::shared_ptr<sph::recv_packet_streamer> my_streamer = +        boost::dynamic_pointer_cast<sph::recv_packet_streamer>(_mbc[mb].rx_streamers[dsp].lock()); +    if (my_streamer.get() == NULL) return; + +    my_streamer->set_samp_rate(rate); +    const double adj = _mbc[mb].rx_dsps[dsp]->get_scaling_adjustment(); +    my_streamer->set_scale_factor(adj); +} + +void usrp2_impl::update_tx_samp_rate(const std::string &mb, const size_t dsp, const double rate){ +    boost::shared_ptr<sph::send_packet_streamer> my_streamer = +        boost::dynamic_pointer_cast<sph::send_packet_streamer>(_mbc[mb].tx_streamers[dsp].lock()); +    if (my_streamer.get() == NULL) return; + +    my_streamer->set_samp_rate(rate); +    const double adj = _mbc[mb].tx_dsp->get_scaling_adjustment(); +    my_streamer->set_scale_factor(adj); +} + +void usrp2_impl::update_rates(void){ +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        fs_path 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").update(); +        } +        BOOST_FOREACH(const std::string &name, _tree->list(root / "tx_dsps")){ +            _tree->access<double>(root / "tx_dsps" / name / "rate" / "value").update(); +        } +    } +} + +void usrp2_impl::update_rx_subdev_spec(const std::string &which_mb, const subdev_spec_t &spec){ +    fs_path 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); +    } +    _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; +} + +void usrp2_impl::update_tx_subdev_spec(const std::string &which_mb, const subdev_spec_t &spec){ +    fs_path 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; +} + +/*********************************************************************** + * Async Data + **********************************************************************/ +bool usrp2_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); +} + +/*********************************************************************** + * Stream destination programmer + **********************************************************************/ +void usrp2_impl::program_stream_dest( +    zero_copy_if::sptr &xport, const uhd::stream_args_t &args +){ +    //perform an initial flush of transport +    while (xport->get_recv_buff(0.0)){} + +    //program the stream command +    usrp2_stream_ctrl_t stream_ctrl = usrp2_stream_ctrl_t(); +    stream_ctrl.sequence = uhd::htonx(boost::uint32_t(0 /* don't care seq num */)); +    stream_ctrl.vrt_hdr = uhd::htonx(boost::uint32_t(USRP2_INVALID_VRT_HEADER)); + +    //user has provided an alternative address and port for destination +    if (args.args.has_key("addr") and args.args.has_key("port")){ +        UHD_MSG(status) << boost::format( +            "Programming streaming destination for custom address.\n" +            "IPv4 Address: %s, UDP Port: %s\n" +        ) % args.args["addr"] % args.args["port"] << std::endl; + +        asio::io_service io_service; +        asio::ip::udp::resolver resolver(io_service); +        asio::ip::udp::resolver::query query(asio::ip::udp::v4(), args.args["addr"], args.args["port"]); +        asio::ip::udp::endpoint endpoint = *resolver.resolve(query); +        stream_ctrl.ip_addr = uhd::htonx(boost::uint32_t(endpoint.address().to_v4().to_ulong())); +        stream_ctrl.udp_port = uhd::htonx(boost::uint32_t(endpoint.port())); + +        for (size_t i = 0; i < 3; i++){ +            UHD_MSG(status) << "ARP attempt " << i << std::endl; +            managed_send_buffer::sptr send_buff = xport->get_send_buff(); +            std::memcpy(send_buff->cast<void *>(), &stream_ctrl, sizeof(stream_ctrl)); +            send_buff->commit(sizeof(stream_ctrl)); +            boost::this_thread::sleep(boost::posix_time::milliseconds(300)); +            managed_recv_buffer::sptr recv_buff = xport->get_recv_buff(0.0); +            if (recv_buff and recv_buff->size() >= sizeof(boost::uint32_t)){ +                const boost::uint32_t result = uhd::ntohx(recv_buff->cast<const boost::uint32_t *>()[0]); +                if (result == 0){ +                    UHD_MSG(status) << "Success! " << std::endl; +                    return; +                } +            } +        } +        throw uhd::runtime_error("Device failed to ARP when programming alternative streaming destination."); +    } + +    else{ +        //send the partial stream control without destination +        managed_send_buffer::sptr send_buff = xport->get_send_buff(); +        std::memcpy(send_buff->cast<void *>(), &stream_ctrl, sizeof(stream_ctrl)); +        send_buff->commit(sizeof(stream_ctrl)/2); +    } +} + +/*********************************************************************** + * Receive streamer + **********************************************************************/ +rx_streamer::sptr usrp2_impl::get_rx_stream(const uhd::stream_args_t &args_){ +    stream_args_t args = args_; + +    //setup defaults for unspecified values +    args.otw_format = args.otw_format.empty()? "sc16" : args.otw_format; +    args.channels = args.channels.empty()? std::vector<size_t>(1, 0) : args.channels; + +    //calculate packet size +    static const size_t hdr_size = 0 +        + vrt::max_if_hdr_words32*sizeof(boost::uint32_t) +        + sizeof(vrt::if_packet_info_t().tlr) //forced to have trailer +        - sizeof(vrt::if_packet_info_t().cid) //no class id ever used +        - sizeof(vrt::if_packet_info_t().tsi) //no int time ever used +    ; +    const size_t bpp = _mbc[_mbc.keys().front()].rx_dsp_xports[0]->get_recv_frame_size() - hdr_size; +    const size_t bpi = convert::get_bytes_per_item(args.otw_format); +    const size_t spp = unsigned(args.args.cast<double>("spp", bpp/bpi)); + +    //make the new streamer given the samples per packet +    boost::shared_ptr<sph::recv_packet_streamer> my_streamer = boost::make_shared<sph::recv_packet_streamer>(spp); + +    //init some streamer stuff +    my_streamer->resize(args.channels.size()); +    my_streamer->set_vrt_unpacker(&vrt::if_hdr_unpack_be); + +    //set the converter +    uhd::convert::id_type id; +    id.input_format = args.otw_format + "_item32_be"; +    id.num_inputs = 1; +    id.output_format = args.cpu_format; +    id.num_outputs = 1; +    my_streamer->set_converter(id); + +    //bind callbacks for the handler +    for (size_t chan_i = 0; chan_i < args.channels.size(); chan_i++){ +        const size_t chan = args.channels[chan_i]; +        size_t num_chan_so_far = 0; +        BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +            num_chan_so_far += _mbc[mb].rx_chan_occ; +            if (chan < num_chan_so_far){ +                const size_t dsp = chan + _mbc[mb].rx_chan_occ - num_chan_so_far; +                _mbc[mb].rx_dsps[dsp]->set_nsamps_per_packet(spp); //seems to be a good place to set this +                _mbc[mb].rx_dsps[dsp]->setup(args); +                this->program_stream_dest(_mbc[mb].rx_dsp_xports[dsp], args); +                my_streamer->set_xport_chan_get_buff(chan_i, boost::bind( +                    &zero_copy_if::get_recv_buff, _mbc[mb].rx_dsp_xports[dsp], _1 +                ), true /*flush*/); +                _mbc[mb].rx_streamers[dsp] = my_streamer; //store weak pointer +                break; +            } +        } +    } + +    //set the packet threshold to be an entire socket buffer's worth +    const size_t packets_per_sock_buff = size_t(50e6/_mbc[_mbc.keys().front()].rx_dsp_xports[0]->get_recv_frame_size()); +    my_streamer->set_alignment_failure_threshold(packets_per_sock_buff); + +    //sets all tick and samp rates on this streamer +    this->update_rates(); + +    return my_streamer; +} + +/*********************************************************************** + * Transmit streamer + **********************************************************************/ +tx_streamer::sptr usrp2_impl::get_tx_stream(const uhd::stream_args_t &args_){ +    stream_args_t args = args_; + +    //setup defaults for unspecified values +    args.otw_format = args.otw_format.empty()? "sc16" : args.otw_format; +    args.channels = args.channels.empty()? std::vector<size_t>(1, 0) : args.channels; + +    //calculate packet size +    static const size_t hdr_size = 0 +        + vrt_send_header_offset_words32*sizeof(boost::uint32_t) +        + vrt::max_if_hdr_words32*sizeof(boost::uint32_t) +        + sizeof(vrt::if_packet_info_t().tlr) //forced to have trailer +        - sizeof(vrt::if_packet_info_t().cid) //no class id ever used +        - sizeof(vrt::if_packet_info_t().sid) //no stream id ever used +        - sizeof(vrt::if_packet_info_t().tsi) //no int time ever used +    ; +    const size_t bpp = _mbc[_mbc.keys().front()].tx_dsp_xport->get_send_frame_size() - hdr_size; +    const size_t spp = bpp/convert::get_bytes_per_item(args.otw_format); + +    //make the new streamer given the samples per packet +    boost::shared_ptr<sph::send_packet_streamer> my_streamer = boost::make_shared<sph::send_packet_streamer>(spp); + +    //init some streamer stuff +    my_streamer->resize(args.channels.size()); +    my_streamer->set_vrt_packer(&vrt::if_hdr_pack_be, vrt_send_header_offset_words32); + +    //set the converter +    uhd::convert::id_type id; +    id.input_format = args.cpu_format; +    id.num_inputs = 1; +    id.output_format = args.otw_format + "_item32_be"; +    id.num_outputs = 1; +    my_streamer->set_converter(id); + +    //bind callbacks for the handler +    for (size_t chan_i = 0; chan_i < args.channels.size(); chan_i++){ +        const size_t chan = args.channels[chan_i]; +        size_t num_chan_so_far = 0; +        size_t abs = 0; +        BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +            num_chan_so_far += _mbc[mb].tx_chan_occ; +            if (chan < num_chan_so_far){ +                const size_t dsp = chan + _mbc[mb].tx_chan_occ - num_chan_so_far; +                if (not args.args.has_key("noclear")){ +                    _io_impl->fc_mons[abs]->clear(); +                } +                _mbc[mb].tx_dsp->setup(args); +                my_streamer->set_xport_chan_get_buff(chan_i, boost::bind( +                    &usrp2_impl::io_impl::get_send_buff, _io_impl.get(), abs, _1 +                )); +                _mbc[mb].tx_streamers[dsp] = my_streamer; //store weak pointer +                break; +            } +            abs += 1; //assume 1 tx dsp +        } +    } + +    //sets all tick and samp rates on this streamer +    this->update_rates(); + +    return my_streamer; +} diff --git a/host/lib/usrp/usrp2/usrp2_clk_regs.hpp b/host/lib/usrp/usrp2/usrp2_clk_regs.hpp new file mode 100644 index 000000000..8b185eac0 --- /dev/null +++ b/host/lib/usrp/usrp2/usrp2_clk_regs.hpp @@ -0,0 +1,87 @@ +// +// Copyright 2010 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_USRP2_CLK_REGS_HPP +#define INCLUDED_USRP2_CLK_REGS_HPP + +#include "usrp2_iface.hpp" + +class usrp2_clk_regs_t { +public: +  usrp2_clk_regs_t(void) { ; } +  usrp2_clk_regs_t(usrp2_iface::rev_type rev) { +    test = 0; +    fpga = 1; +    dac = 3; + +    switch(rev) { +    case usrp2_iface::USRP2_REV3: +        exp = 2; +        adc = 4; +        serdes = 2; +        tx_db = 6; +        break; +    case usrp2_iface::USRP2_REV4: +        exp = 5; +        adc = 4; +        serdes = 2; +        tx_db = 6; +        break; +    case usrp2_iface::USRP_N200: +    case usrp2_iface::USRP_N210: +    case usrp2_iface::USRP_N200_R4: +    case usrp2_iface::USRP_N210_R4: +        exp = 6; +        adc = 2; +        serdes = 4; +        tx_db = 5; +        break; +    case usrp2_iface::USRP_NXXX: +        //dont throw, it may be unitialized +        break; +    } +     +    rx_db = 7; +  } + +  static int output(int clknum) { return 0x3C + clknum; } +  static int div_lo(int clknum) { return 0x48 + 2 * clknum; } +  static int div_hi(int clknum) { return 0x49 + 2 * clknum; } + +  const static int acounter = 0x04; +  const static int bcounter_msb = 0x05; +  const static int bcounter_lsb = 0x06; +  const static int pll_1 = 0x07; +  const static int pll_2 = 0x08; +  const static int pll_3 = 0x09; +  const static int pll_4 = 0x0A; +  const static int ref_counter_msb = 0x0B; +  const static int ref_counter_lsb = 0x0C; +  const static int pll_5 = 0x0D; +  const static int update = 0x5A; + +  int test; +  int fpga; +  int adc; +  int dac; +  int serdes; +  int exp; +  int tx_db; +  int rx_db; +}; + +#endif //INCLUDED_USRP2_CLK_REGS_HPP diff --git a/host/lib/usrp/usrp2/usrp2_fifo_ctrl.cpp b/host/lib/usrp/usrp2/usrp2_fifo_ctrl.cpp new file mode 100644 index 000000000..efb88eb82 --- /dev/null +++ b/host/lib/usrp/usrp2/usrp2_fifo_ctrl.cpp @@ -0,0 +1,244 @@ +// +// Copyright 2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "usrp2_regs.hpp" +#include <uhd/exception.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/utils/safe_call.hpp> +#include <uhd/transport/vrt_if_packet.hpp> +#include "usrp2_fifo_ctrl.hpp" +#include <boost/thread/mutex.hpp> +#include <boost/thread/thread.hpp> +#include <boost/asio.hpp> //htonl +#include <boost/format.hpp> + +using namespace uhd; +using namespace uhd::transport; + +static const size_t POKE32_CMD = (1 << 8); +static const size_t PEEK32_CMD = 0; +static const double ACK_TIMEOUT = 0.5; +static const double MASSIVE_TIMEOUT = 10.0; //for when we wait on a timed command +static const boost::uint32_t MAX_SEQS_OUT = 15; + +#define SPI_DIV SR_SPI_CORE + 0 +#define SPI_CTRL SR_SPI_CORE + 1 +#define SPI_DATA SR_SPI_CORE + 2 +#define SPI_READBACK 0 +// spi clock rate = master_clock/(div+1)/2 (10MHz in this case) +#define SPI_DIVIDER 4 + +class usrp2_fifo_ctrl_impl : public usrp2_fifo_ctrl{ +public: + +    usrp2_fifo_ctrl_impl(zero_copy_if::sptr xport): +        _xport(xport), +        _seq_out(0), +        _seq_ack(0), +        _timeout(ACK_TIMEOUT) +    { +        while (_xport->get_recv_buff(0.0)){} //flush +        this->set_time(uhd::time_spec_t(0.0)); +        this->set_tick_rate(1.0); //something possible but bogus +        this->init_spi(); +    } + +    ~usrp2_fifo_ctrl_impl(void){ +        _timeout = ACK_TIMEOUT; //reset timeout to something small +        UHD_SAFE_CALL( +            this->peek32(0); //dummy peek with the purpose of ack'ing all packets +        ) +    } + +    /******************************************************************* +     * Peek and poke 32 bit implementation +     ******************************************************************/ +    void poke32(wb_addr_type addr, boost::uint32_t data){ +        boost::mutex::scoped_lock lock(_mutex); + +        this->send_pkt((addr - SETTING_REGS_BASE)/4, data, POKE32_CMD); + +        this->wait_for_ack(_seq_out-MAX_SEQS_OUT); +    } + +    boost::uint32_t peek32(wb_addr_type addr){ +        boost::mutex::scoped_lock lock(_mutex); + +        this->send_pkt((addr - READBACK_BASE)/4, 0, PEEK32_CMD); + +        return this->wait_for_ack(_seq_out); +    } + +    /******************************************************************* +     * Peek and poke 16 bit not implemented +     ******************************************************************/ +    void poke16(wb_addr_type, boost::uint16_t){ +        throw uhd::not_implemented_error("poke16 not implemented in fifo ctrl module"); +    } + +    boost::uint16_t peek16(wb_addr_type){ +        throw uhd::not_implemented_error("peek16 not implemented in fifo ctrl module"); +    } + +    /******************************************************************* +     * FIFO controlled SPI implementation +     ******************************************************************/ +    void init_spi(void){ +        boost::mutex::scoped_lock lock(_mutex); + +        this->send_pkt(SPI_DIV, SPI_DIVIDER, POKE32_CMD); +        this->wait_for_ack(_seq_out-MAX_SEQS_OUT); + +        _ctrl_word_cache = 0; // force update first time around +    } + +    boost::uint32_t transact_spi( +        int which_slave, +        const spi_config_t &config, +        boost::uint32_t data, +        size_t num_bits, +        bool readback +    ){ +        boost::mutex::scoped_lock lock(_mutex); + +        //load control word +        boost::uint32_t ctrl_word = 0; +        ctrl_word |= ((which_slave & 0xffffff) << 0); +        ctrl_word |= ((num_bits & 0x3ff) << 24); +        if (config.mosi_edge == spi_config_t::EDGE_FALL) ctrl_word |= (1 << 31); +        if (config.miso_edge == spi_config_t::EDGE_RISE) ctrl_word |= (1 << 30); + +        //load data word (must be in upper bits) +        const boost::uint32_t data_out = data << (32 - num_bits); + +        //conditionally send control word +        if (_ctrl_word_cache != ctrl_word){ +            this->send_pkt(SPI_CTRL, ctrl_word, POKE32_CMD); +            this->wait_for_ack(_seq_out-MAX_SEQS_OUT); +            _ctrl_word_cache = ctrl_word; +        } + +        //send data word +        this->send_pkt(SPI_DATA, data_out, POKE32_CMD); +        this->wait_for_ack(_seq_out-MAX_SEQS_OUT); + +        //conditional readback +        if (readback){ +            this->send_pkt(SPI_READBACK, 0, PEEK32_CMD); +            return this->wait_for_ack(_seq_out); +        } + +        return 0; +    } + +    /******************************************************************* +     * Update methods for time +     ******************************************************************/ +    void set_time(const uhd::time_spec_t &time){ +        boost::mutex::scoped_lock lock(_mutex); +        _time = time; +        _use_time = _time != uhd::time_spec_t(0.0); +        if (_use_time) _timeout = MASSIVE_TIMEOUT; //permanently sets larger timeout +    } + +    void set_tick_rate(const double rate){ +        boost::mutex::scoped_lock lock(_mutex); +        _tick_rate = rate; +    } + +private: + +    /******************************************************************* +     * Primary control and interaction private methods +     ******************************************************************/ +    UHD_INLINE void send_pkt(wb_addr_type addr, boost::uint32_t data, int cmd){ +        managed_send_buffer::sptr buff = _xport->get_send_buff(0.0); +        if (not buff){ +            throw uhd::runtime_error("fifo ctrl timed out getting a send buffer"); +        } +        boost::uint32_t *trans = buff->cast<boost::uint32_t *>(); +        trans[0] = htonl(++_seq_out); +        boost::uint32_t *pkt = trans + 1; + +        //load packet info +        vrt::if_packet_info_t packet_info; +        packet_info.packet_type = vrt::if_packet_info_t::PACKET_TYPE_CONTEXT; +        packet_info.num_payload_words32 = 2; +        packet_info.num_payload_bytes = packet_info.num_payload_words32*sizeof(boost::uint32_t); +        packet_info.packet_count = _seq_out; +        packet_info.tsf = _time.to_ticks(_tick_rate); +        packet_info.sob = false; +        packet_info.eob = false; +        packet_info.has_sid = false; +        packet_info.has_cid = false; +        packet_info.has_tsi = false; +        packet_info.has_tsf = _use_time; +        packet_info.has_tlr = false; + +        //load header +        vrt::if_hdr_pack_be(pkt, packet_info); + +        //load payload +        const boost::uint32_t ctrl_word = (addr & 0xff) | cmd | (_seq_out << 16); +        pkt[packet_info.num_header_words32+0] = htonl(ctrl_word); +        pkt[packet_info.num_header_words32+1] = htonl(data); + +        //send the buffer over the interface +        buff->commit(sizeof(boost::uint32_t)*(packet_info.num_packet_words32+1)); +    } + +    UHD_INLINE bool wraparound_lt16(const boost::int16_t i0, const boost::int16_t i1){ +        if (((i0 ^ i1) & 0x8000) == 0) //same sign bits +            return boost::uint16_t(i0) < boost::uint16_t(i1); +        return boost::int16_t(i1 - i0) > 0; +    } + +    UHD_INLINE boost::uint32_t wait_for_ack(const boost::uint16_t seq_to_ack){ + +        while (wraparound_lt16(_seq_ack, seq_to_ack)){ +            managed_recv_buffer::sptr buff = _xport->get_recv_buff(_timeout); +            if (not buff){ +                throw uhd::runtime_error("fifo ctrl timed out looking for acks"); +            } +            const boost::uint32_t *pkt = buff->cast<const boost::uint32_t *>(); +            vrt::if_packet_info_t packet_info; +            packet_info.num_packet_words32 = buff->size()/sizeof(boost::uint32_t); +            vrt::if_hdr_unpack_be(pkt, packet_info); +            _seq_ack = ntohl(pkt[packet_info.num_header_words32+0]) >> 16; +            if (_seq_ack == seq_to_ack){ +                return ntohl(pkt[packet_info.num_header_words32+1]); +            } +        } + +        return 0; +    } + +    zero_copy_if::sptr _xport; +    boost::mutex _mutex; +    boost::uint16_t _seq_out; +    boost::uint16_t _seq_ack; +    uhd::time_spec_t _time; +    bool _use_time; +    double _tick_rate; +    double _timeout; +    boost::uint32_t _ctrl_word_cache; +}; + + +usrp2_fifo_ctrl::sptr usrp2_fifo_ctrl::make(zero_copy_if::sptr xport){ +    return sptr(new usrp2_fifo_ctrl_impl(xport)); +} diff --git a/host/lib/usrp/usrp2/usrp2_fifo_ctrl.hpp b/host/lib/usrp/usrp2/usrp2_fifo_ctrl.hpp new file mode 100644 index 000000000..b48d05aa2 --- /dev/null +++ b/host/lib/usrp/usrp2/usrp2_fifo_ctrl.hpp @@ -0,0 +1,47 @@ +// +// Copyright 2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_USRP2_FIFO_CTRL_HPP +#define INCLUDED_USRP2_FIFO_CTRL_HPP + +#include <uhd/types/time_spec.hpp> +#include <uhd/types/serial.hpp> +#include <uhd/transport/zero_copy.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> +#include "wb_iface.hpp" +#include <string> + +/*! + * The usrp2 FIFO control class: + * Provide high-speed peek/poke interface. + */ +class usrp2_fifo_ctrl : public wb_iface, public uhd::spi_iface{ +public: +    typedef boost::shared_ptr<usrp2_fifo_ctrl> sptr; + +    //! Make a new FIFO control object +    static sptr make(uhd::transport::zero_copy_if::sptr xport); + +    //! Set the command time that will activate +    virtual void set_time(const uhd::time_spec_t &time) = 0; + +    //! Set the tick rate (converting time into ticks) +    virtual void set_tick_rate(const double rate) = 0; +}; + +#endif /* INCLUDED_USRP2_FIFO_CTRL_HPP */ diff --git a/host/lib/usrp/usrp2/usrp2_iface.cpp b/host/lib/usrp/usrp2/usrp2_iface.cpp new file mode 100644 index 000000000..f0b2a90a6 --- /dev/null +++ b/host/lib/usrp/usrp2/usrp2_iface.cpp @@ -0,0 +1,447 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "usrp2_regs.hpp" +#include "usrp2_impl.hpp" +#include "fw_common.h" +#include "usrp2_iface.hpp" +#include <uhd/exception.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/utils/tasks.hpp> +#include <uhd/utils/images.hpp> +#include <uhd/utils/safe_call.hpp> +#include <uhd/types/dict.hpp> +#include <boost/thread.hpp> +#include <boost/foreach.hpp> +#include <boost/asio.hpp> //used for htonl and ntohl +#include <boost/assign/list_of.hpp> +#include <boost/format.hpp> +#include <boost/bind.hpp> +#include <boost/tokenizer.hpp> +#include <boost/functional/hash.hpp> +#include <boost/filesystem.hpp> +#include <algorithm> +#include <iostream> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; +namespace fs = boost::filesystem; + +static const double CTRL_RECV_TIMEOUT = 1.0; +static const size_t CTRL_RECV_RETRIES = 3; + +//custom timeout error for retry logic to catch/retry +struct timeout_error : uhd::runtime_error +{ +    timeout_error(const std::string &what): +        uhd::runtime_error(what) +    { +        //NOP +    } +}; + +static const boost::uint32_t MIN_PROTO_COMPAT_SPI = 7; +static const boost::uint32_t MIN_PROTO_COMPAT_I2C = 7; +// The register compat number must reflect the protocol compatibility +// and the compatibility of the register mapping (more likely to change). +static const boost::uint32_t MIN_PROTO_COMPAT_REG = 10; +static const boost::uint32_t MIN_PROTO_COMPAT_UART = 7; + +//Define get_gpid() to get a globally unique identifier for this process. +//The gpid is implemented as a hash of the pid and a unique machine identifier. +#ifdef UHD_PLATFORM_WIN32 +#include <Windows.h> +static inline size_t get_gpid(void){ +    //extract volume serial number +    char szVolName[MAX_PATH+1], szFileSysName[MAX_PATH+1]; +    DWORD dwSerialNumber, dwMaxComponentLen, dwFileSysFlags; +    GetVolumeInformation("C:\\", szVolName, MAX_PATH, +        &dwSerialNumber, &dwMaxComponentLen, +        &dwFileSysFlags, szFileSysName, sizeof(szFileSysName)); + +    size_t hash = 0; +    boost::hash_combine(hash, GetCurrentProcessId()); +    boost::hash_combine(hash, dwSerialNumber); +    return hash; +} +#else +#include <unistd.h> +static inline size_t get_gpid(void){ +    size_t hash = 0; +    boost::hash_combine(hash, getpid()); +    boost::hash_combine(hash, gethostid()); +    return hash; +} +#endif + +class usrp2_iface_impl : public usrp2_iface{ +public: +/*********************************************************************** + * Structors + **********************************************************************/ +    usrp2_iface_impl(udp_simple::sptr ctrl_transport): +        _ctrl_transport(ctrl_transport), +        _ctrl_seq_num(0), +        _protocol_compat(0) //initialized below... +    { +        //Obtain the firmware's compat number. +        //Save the response compat number for communication. +        //TODO can choose to reject certain older compat numbers +        usrp2_ctrl_data_t ctrl_data = usrp2_ctrl_data_t(); +        ctrl_data.id = htonl(USRP2_CTRL_ID_WAZZUP_BRO); +        ctrl_data = ctrl_send_and_recv(ctrl_data, 0, ~0); +        if (ntohl(ctrl_data.id) != USRP2_CTRL_ID_WAZZUP_DUDE) +            throw uhd::runtime_error("firmware not responding"); +        _protocol_compat = ntohl(ctrl_data.proto_ver); + +        mb_eeprom = mboard_eeprom_t(*this, USRP2_EEPROM_MAP_KEY); +    } + +    ~usrp2_iface_impl(void){UHD_SAFE_CALL( +        this->lock_device(false); +    )} + +/*********************************************************************** + * Device locking + **********************************************************************/ + +    void lock_device(bool lock){ +        if (lock){ +            this->pokefw(U2_FW_REG_LOCK_GPID, boost::uint32_t(get_gpid())); +            _lock_task = task::make(boost::bind(&usrp2_iface_impl::lock_task, this)); +        } +        else{ +            _lock_task.reset(); //shutdown the task +            this->pokefw(U2_FW_REG_LOCK_TIME, 0); //unlock +        } +    } + +    bool is_device_locked(void){ +        //never assume lock with fpga image mismatch +        if ((this->peek32(U2_REG_COMPAT_NUM_RB) >> 16) != USRP2_FPGA_COMPAT_NUM) return false; + +        boost::uint32_t lock_time = this->peekfw(U2_FW_REG_LOCK_TIME); +        boost::uint32_t lock_gpid = this->peekfw(U2_FW_REG_LOCK_GPID); + +        //may not be the right tick rate, but this is ok for locking purposes +        const boost::uint32_t lock_timeout_time = boost::uint32_t(3*100e6); + +        //if the difference is larger, assume not locked anymore +        if ((lock_time & 1) == 0) return false; //bit0 says unlocked +        const boost::uint32_t time_diff = this->get_curr_time() - lock_time; +        if (time_diff >= lock_timeout_time) return false; + +        //otherwise only lock if the device hash is different that ours +        return lock_gpid != boost::uint32_t(get_gpid()); +    } + +    void lock_task(void){ +        //re-lock in task +        this->pokefw(U2_FW_REG_LOCK_TIME, this->get_curr_time()); +        //sleep for a bit +        boost::this_thread::sleep(boost::posix_time::milliseconds(1500)); +    } + +    boost::uint32_t get_curr_time(void){ +        return this->peek32(U2_REG_TIME64_LO_RB_IMM) | 1; //bit 1 says locked +    } + +/*********************************************************************** + * Peek and Poke + **********************************************************************/ +    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(wb_addr_type addr){ +        return this->get_reg<boost::uint32_t, USRP2_REG_ACTION_FPGA_PEEK32>(addr); +    } + +    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(wb_addr_type addr){ +        return this->get_reg<boost::uint16_t, USRP2_REG_ACTION_FPGA_PEEK16>(addr); +    } + +    void pokefw(wb_addr_type addr, boost::uint32_t data) +    { +        this->get_reg<boost::uint32_t, USRP2_REG_ACTION_FW_POKE32>(addr, data); +    } + +    boost::uint32_t peekfw(wb_addr_type addr) +    { +        return this->get_reg<boost::uint32_t, USRP2_REG_ACTION_FW_PEEK32>(addr); +    } + +    template <class T, usrp2_reg_action_t action> +    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); +        out_data.data.reg_args.addr = htonl(addr); +        out_data.data.reg_args.data = htonl(boost::uint32_t(data)); +        out_data.data.reg_args.action = action; + +        //send and recv +        usrp2_ctrl_data_t in_data = this->ctrl_send_and_recv(out_data, MIN_PROTO_COMPAT_REG); +        UHD_ASSERT_THROW(ntohl(in_data.id) == USRP2_CTRL_ID_OMG_GOT_REGISTER_SO_BAD_DUDE); +        return T(ntohl(in_data.data.reg_args.data)); +    } + +/*********************************************************************** + * SPI + **********************************************************************/ +    boost::uint32_t transact_spi( +        int which_slave, +        const spi_config_t &config, +        boost::uint32_t data, +        size_t num_bits, +        bool readback +    ){ +        static const uhd::dict<spi_config_t::edge_t, int> spi_edge_to_otw = boost::assign::map_list_of +            (spi_config_t::EDGE_RISE, USRP2_CLK_EDGE_RISE) +            (spi_config_t::EDGE_FALL, USRP2_CLK_EDGE_FALL) +        ; + +        //setup the out data +        usrp2_ctrl_data_t out_data = usrp2_ctrl_data_t(); +        out_data.id = htonl(USRP2_CTRL_ID_TRANSACT_ME_SOME_SPI_BRO); +        out_data.data.spi_args.dev = htonl(which_slave); +        out_data.data.spi_args.miso_edge = spi_edge_to_otw[config.miso_edge]; +        out_data.data.spi_args.mosi_edge = spi_edge_to_otw[config.mosi_edge]; +        out_data.data.spi_args.readback = (readback)? 1 : 0; +        out_data.data.spi_args.num_bits = num_bits; +        out_data.data.spi_args.data = htonl(data); + +        //send and recv +        usrp2_ctrl_data_t in_data = this->ctrl_send_and_recv(out_data, MIN_PROTO_COMPAT_SPI); +        UHD_ASSERT_THROW(ntohl(in_data.id) == USRP2_CTRL_ID_OMG_TRANSACTED_SPI_DUDE); + +        return ntohl(in_data.data.spi_args.data); +    } + +/*********************************************************************** + * I2C + **********************************************************************/ +    void write_i2c(boost::uint8_t addr, const byte_vector_t &buf){ +        //setup the out data +        usrp2_ctrl_data_t out_data = usrp2_ctrl_data_t(); +        out_data.id = htonl(USRP2_CTRL_ID_WRITE_THESE_I2C_VALUES_BRO); +        out_data.data.i2c_args.addr = addr; +        out_data.data.i2c_args.bytes = buf.size(); + +        //limitation of i2c transaction size +        UHD_ASSERT_THROW(buf.size() <= sizeof(out_data.data.i2c_args.data)); + +        //copy in the data +        std::copy(buf.begin(), buf.end(), out_data.data.i2c_args.data); + +        //send and recv +        usrp2_ctrl_data_t in_data = this->ctrl_send_and_recv(out_data, MIN_PROTO_COMPAT_I2C); +        UHD_ASSERT_THROW(ntohl(in_data.id) == USRP2_CTRL_ID_COOL_IM_DONE_I2C_WRITE_DUDE); +    } + +    byte_vector_t read_i2c(boost::uint8_t addr, size_t num_bytes){ +        //setup the out data +        usrp2_ctrl_data_t out_data = usrp2_ctrl_data_t(); +        out_data.id = htonl(USRP2_CTRL_ID_DO_AN_I2C_READ_FOR_ME_BRO); +        out_data.data.i2c_args.addr = addr; +        out_data.data.i2c_args.bytes = num_bytes; + +        //limitation of i2c transaction size +        UHD_ASSERT_THROW(num_bytes <= sizeof(out_data.data.i2c_args.data)); + +        //send and recv +        usrp2_ctrl_data_t in_data = this->ctrl_send_and_recv(out_data, MIN_PROTO_COMPAT_I2C); +        UHD_ASSERT_THROW(ntohl(in_data.id) == USRP2_CTRL_ID_HERES_THE_I2C_DATA_DUDE); +        UHD_ASSERT_THROW(in_data.data.i2c_args.addr = num_bytes); + +        //copy out the data +        byte_vector_t result(num_bytes); +        std::copy(in_data.data.i2c_args.data, in_data.data.i2c_args.data + num_bytes, result.begin()); +        return result; +    } + +/*********************************************************************** + * Send/Recv over control + **********************************************************************/ +    usrp2_ctrl_data_t ctrl_send_and_recv( +        const usrp2_ctrl_data_t &out_data, +        boost::uint32_t lo = USRP2_FW_COMPAT_NUM, +        boost::uint32_t hi = USRP2_FW_COMPAT_NUM +    ){ +        boost::mutex::scoped_lock lock(_ctrl_mutex); + +        for (size_t i = 0; i < CTRL_RECV_RETRIES; i++){ +            try{ +                return ctrl_send_and_recv_internal(out_data, lo, hi, CTRL_RECV_TIMEOUT/CTRL_RECV_RETRIES); +            } +            catch(const timeout_error &e){ +                UHD_MSG(error) +                    << "Control packet attempt " << i +                    << ", sequence number " << _ctrl_seq_num +                    << ":\n" << e.what() << std::endl; +            } +        } +        throw uhd::runtime_error("link dead: timeout waiting for control packet ACK"); +    } + +    usrp2_ctrl_data_t ctrl_send_and_recv_internal( +        const usrp2_ctrl_data_t &out_data, +        boost::uint32_t lo, boost::uint32_t hi, +        const double timeout +    ){ +        //fill in the seq number and send +        usrp2_ctrl_data_t out_copy = out_data; +        out_copy.proto_ver = htonl(_protocol_compat); +        out_copy.seq = htonl(++_ctrl_seq_num); +        _ctrl_transport->send(boost::asio::buffer(&out_copy, sizeof(usrp2_ctrl_data_t))); + +        //loop until we get the packet or timeout +        boost::uint8_t usrp2_ctrl_data_in_mem[udp_simple::mtu]; //allocate max bytes for recv +        const usrp2_ctrl_data_t *ctrl_data_in = reinterpret_cast<const usrp2_ctrl_data_t *>(usrp2_ctrl_data_in_mem); +        while(true){ +            size_t len = _ctrl_transport->recv(boost::asio::buffer(usrp2_ctrl_data_in_mem), timeout); +            boost::uint32_t compat = ntohl(ctrl_data_in->proto_ver); +            if(len >= sizeof(boost::uint32_t) and (hi < compat or lo > compat)){ +                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 protocol compatibility number %s, but got %d:\n" +                    "The firmware build is not compatible with the host code build.\n" +                    "%s\n" +                ) % ((lo == hi)? (boost::format("%d") % hi) : (boost::format("[%d to %d]") % lo % hi)) +                  % compat % this->images_warn_help_message())); +            } +            if (len >= sizeof(usrp2_ctrl_data_t) and ntohl(ctrl_data_in->seq) == _ctrl_seq_num){ +                return *ctrl_data_in; +            } +            if (len == 0) break; //timeout +            //didnt get seq or bad packet, continue looking... +        } +        throw timeout_error("no control response, possible packet loss"); +    } + +    rev_type get_rev(void){ +        std::string hw = mb_eeprom["hardware"]; +        if (hw.empty()) return USRP_NXXX; +        switch (boost::lexical_cast<boost::uint16_t>(hw)){ +        case 0x0300: +        case 0x0301: return USRP2_REV3; +        case 0x0400: return USRP2_REV4; +        case 0x0A00: return USRP_N200; +        case 0x0A01: return USRP_N210; +        case 0x0A10: return USRP_N200_R4; +        case 0x0A11: return USRP_N210_R4; +        } +        return USRP_NXXX; //unknown type +    } + +    const std::string get_cname(void){ +        switch(this->get_rev()){ +        case USRP2_REV3: return "USRP2 r3"; +        case USRP2_REV4: return "USRP2 r4"; +        case USRP_N200: return "N200"; +        case USRP_N210: return "N210"; +        case USRP_N200_R4: return "N200r4"; +        case USRP_N210_R4: return "N210r4"; +        case USRP_NXXX: return "N???"; +        } +        UHD_THROW_INVALID_CODE_PATH(); +    } + +    const std::string get_fw_version_string(void){ +        boost::uint32_t minor = this->get_reg<boost::uint32_t, USRP2_REG_ACTION_FW_PEEK32>(U2_FW_REG_VER_MINOR); +        return str(boost::format("%u.%u") % _protocol_compat % minor); +    } + +    std::string images_warn_help_message(void){ +        //determine the images names +        std::string fw_image, fpga_image; +        switch(this->get_rev()){ +        case USRP2_REV3:   fpga_image = "usrp2_fpga.bin";        fw_image = "usrp2_fw.bin";     break; +        case USRP2_REV4:   fpga_image = "usrp2_fpga.bin";        fw_image = "usrp2_fw.bin";     break; +        case USRP_N200:    fpga_image = "usrp_n200_r2_fpga.bin"; fw_image = "usrp_n200_fw.bin"; break; +        case USRP_N210:    fpga_image = "usrp_n210_r2_fpga.bin"; fw_image = "usrp_n210_fw.bin"; break; +        case USRP_N200_R4: fpga_image = "usrp_n200_r4_fpga.bin"; fw_image = "usrp_n200_fw.bin"; break; +        case USRP_N210_R4: fpga_image = "usrp_n210_r4_fpga.bin"; fw_image = "usrp_n210_fw.bin"; break; +        default: break; +        } +        if (fw_image.empty() or fpga_image.empty()) return ""; + +        //does your platform use sudo? +        std::string sudo; +        #if defined(UHD_PLATFORM_LINUX) || defined(UHD_PLATFORM_MACOS) +            sudo = "sudo "; +        #endif + + +        //look up the real FS path to the images +        std::string fw_image_path, fpga_image_path; +        try{ +            fw_image_path = uhd::find_image_path(fw_image); +            fpga_image_path = uhd::find_image_path(fpga_image); +        } +        catch(const std::exception &){ +            return str(boost::format("Could not find %s and %s in your images path!\n%s") % fw_image % fpga_image % print_images_error()); +        } + +        //escape char for multi-line cmd + newline + indent? +        #ifdef UHD_PLATFORM_WIN32 +            const std::string ml = "^\n    "; +        #else +            const std::string ml = "\\\n    "; +        #endif + +        //create the images downloader and burner commands +        const std::string images_downloader_cmd = str(boost::format("%s\"%s\"") % sudo % find_images_downloader()); +        if (this->get_rev() == USRP2_REV3 or this->get_rev() == USRP2_REV4){ +            const std::string card_burner = (fs::path(fw_image_path).branch_path().branch_path() / "utils" / "usrp2_card_burner.py").string(); +            const std::string card_burner_cmd = str(boost::format("\"%s%s\" %s--fpga=\"%s\" %s--fw=\"%s\"") % sudo % card_burner % ml % fpga_image_path % ml % fw_image_path); +            return str(boost::format("%s\n%s") % print_images_error() % card_burner_cmd); +        } +        else{ +            const std::string addr = _ctrl_transport->get_recv_addr(); +            const std::string net_burner = (fs::path(fw_image_path).branch_path().branch_path() / "utils" / "usrp_n2xx_net_burner.py").string(); +            const std::string net_burner_cmd = str(boost::format("\"%s\" %s--fpga=\"%s\" %s--fw=\"%s\" %s--addr=\"%s\"") % net_burner % ml % fpga_image_path % ml % fw_image_path % ml % addr); +            return str(boost::format("%s\n%s") % print_images_error() % net_burner_cmd); +        } +    } + +private: +    //this lovely lady makes it all possible +    udp_simple::sptr _ctrl_transport; + +    //used in send/recv +    boost::mutex _ctrl_mutex; +    boost::uint32_t _ctrl_seq_num; +    boost::uint32_t _protocol_compat; + +    //lock thread stuff +    task::sptr _lock_task; +}; + +/*********************************************************************** + * Public make function for usrp2 interface + **********************************************************************/ +usrp2_iface::sptr usrp2_iface::make(udp_simple::sptr ctrl_transport){ +    return usrp2_iface::sptr(new usrp2_iface_impl(ctrl_transport)); +} + diff --git a/host/lib/usrp/usrp2/usrp2_iface.hpp b/host/lib/usrp/usrp2/usrp2_iface.hpp new file mode 100644 index 000000000..ed4de02d5 --- /dev/null +++ b/host/lib/usrp/usrp2/usrp2_iface.hpp @@ -0,0 +1,85 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_USRP2_IFACE_HPP +#define INCLUDED_USRP2_IFACE_HPP + +#include <uhd/transport/udp_simple.hpp> +#include <uhd/types/serial.hpp> +#include <uhd/usrp/mboard_eeprom.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> +#include <boost/function.hpp> +#include "usrp2_regs.hpp" +#include "wb_iface.hpp" +#include <string> + +/*! + * The usrp2 interface class: + * Provides a set of functions to implementation layer. + * Including spi, peek, poke, control... + */ +class usrp2_iface : public wb_iface, public uhd::spi_iface, public uhd::i2c_iface{ +public: +    typedef boost::shared_ptr<usrp2_iface> sptr; +    /*! +     * Make a new usrp2 interface with the control transport. +     * \param ctrl_transport the udp transport object +     * \return a new usrp2 interface object +     */ +    static sptr make(uhd::transport::udp_simple::sptr ctrl_transport); + +    //! poke a register in the virtual fw table +    virtual void pokefw(wb_addr_type addr, boost::uint32_t data) = 0; + +    //! peek a register in the virtual fw table +    virtual boost::uint32_t peekfw(wb_addr_type addr) = 0; + +    //! The list of possible revision types +    enum rev_type { +        USRP2_REV3 = 3, +        USRP2_REV4 = 4, +        USRP_N200 = 200, +        USRP_N200_R4 = 201, +        USRP_N210 = 210, +        USRP_N210_R4 = 211, +        USRP_NXXX = 0 +    }; + +    //! Get the revision type for this device +    virtual rev_type get_rev(void) = 0; + +    //! Get the canonical name for this device +    virtual const std::string get_cname(void) = 0; + +    //! Lock the device to this iface +    virtual void lock_device(bool lock) = 0; + +    //! Is this device locked? +    virtual bool is_device_locked(void) = 0; + +    //! A version string for firmware +    virtual const std::string get_fw_version_string(void) = 0; + +    //! Construct a helpful warning message for images +    virtual std::string images_warn_help_message(void) = 0; + +    //motherboard eeprom map structure +    uhd::usrp::mboard_eeprom_t mb_eeprom; +}; + +#endif /* INCLUDED_USRP2_IFACE_HPP */ diff --git a/host/lib/usrp/usrp2/usrp2_impl.cpp b/host/lib/usrp/usrp2/usrp2_impl.cpp new file mode 100644 index 000000000..42b1acc4c --- /dev/null +++ b/host/lib/usrp/usrp2/usrp2_impl.cpp @@ -0,0 +1,843 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#include "usrp2_impl.hpp" +#include "fw_common.h" +#include "apply_corrections.hpp" +#include <uhd/utils/log.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/exception.hpp> +#include <uhd/transport/if_addrs.hpp> +#include <uhd/transport/udp_zero_copy.hpp> +#include <uhd/types/ranges.hpp> +#include <uhd/exception.hpp> +#include <uhd/utils/static.hpp> +#include <uhd/utils/byteswap.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 + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; +namespace asio = boost::asio; + +/*********************************************************************** + * Discovery over the udp transport + **********************************************************************/ +static device_addrs_t usrp2_find(const device_addr_t &hint_){ +    //handle the multi-device discovery +    device_addrs_t hints = separate_device_addr(hint_); +    if (hints.size() > 1){ +        device_addrs_t found_devices; +        BOOST_FOREACH(const device_addr_t &hint_i, hints){ +            device_addrs_t found_devices_i = usrp2_find(hint_i); +            if (found_devices_i.size() != 1) throw uhd::value_error(str(boost::format( +                "Could not resolve device hint \"%s\" to a single device." +            ) % hint_i.to_string())); +            found_devices.push_back(found_devices_i[0]); +        } +        return device_addrs_t(1, combine_device_addrs(found_devices)); +    } + +    //initialize the hint for a single device case +    UHD_ASSERT_THROW(hints.size() <= 1); +    hints.resize(1); //in case it was empty +    device_addr_t hint = hints[0]; +    device_addrs_t usrp2_addrs; + +    //return an empty list of addresses when type is set to non-usrp2 +    if (hint.has_key("type") and hint["type"] != "usrp2") return usrp2_addrs; + +    //if no address was specified, send a broadcast on each interface +    if (not hint.has_key("addr")){ +        BOOST_FOREACH(const if_addrs_t &if_addrs, get_if_addrs()){ +            //avoid the loopback device +            if (if_addrs.inet == asio::ip::address_v4::loopback().to_string()) continue; + +            //create a new hint with this broadcast address +            device_addr_t new_hint = hint; +            new_hint["addr"] = if_addrs.bcast; + +            //call discover with the new hint and append results +            device_addrs_t new_usrp2_addrs = usrp2_find(new_hint); +            usrp2_addrs.insert(usrp2_addrs.begin(), +                new_usrp2_addrs.begin(), new_usrp2_addrs.end() +            ); +        } +        return usrp2_addrs; +    } + +    //Create a UDP transport to communicate: +    //Some devices will cause a throw when opened for a broadcast address. +    //We print and recover so the caller can loop through all bcast addrs. +    udp_simple::sptr udp_transport; +    try{ +        udp_transport = udp_simple::make_broadcast(hint["addr"], BOOST_STRINGIZE(USRP2_UDP_CTRL_PORT)); +    } +    catch(const std::exception &e){ +        UHD_MSG(error) << boost::format("Cannot open UDP transport on %s\n%s") % hint["addr"] % e.what() << std::endl; +        return usrp2_addrs; //dont throw, but return empty address so caller can insert +    } + +    //send a hello control packet +    usrp2_ctrl_data_t ctrl_data_out = usrp2_ctrl_data_t(); +    ctrl_data_out.proto_ver = uhd::htonx<boost::uint32_t>(USRP2_FW_COMPAT_NUM); +    ctrl_data_out.id = uhd::htonx<boost::uint32_t>(USRP2_CTRL_ID_WAZZUP_BRO); +    udp_transport->send(boost::asio::buffer(&ctrl_data_out, sizeof(ctrl_data_out))); + +    //loop and recieve until the timeout +    boost::uint8_t usrp2_ctrl_data_in_mem[udp_simple::mtu]; //allocate max bytes for recv +    const usrp2_ctrl_data_t *ctrl_data_in = reinterpret_cast<const usrp2_ctrl_data_t *>(usrp2_ctrl_data_in_mem); +    while(true){ +        size_t len = udp_transport->recv(asio::buffer(usrp2_ctrl_data_in_mem)); +        if (len > offsetof(usrp2_ctrl_data_t, data) and ntohl(ctrl_data_in->id) == USRP2_CTRL_ID_WAZZUP_DUDE){ + +            //make a boost asio ipv4 with the raw addr in host byte order +            device_addr_t new_addr; +            new_addr["type"] = "usrp2"; +            //We used to get the address from the control packet. +            //Now now uses the socket itself to yield the address. +            //boost::asio::ip::address_v4 ip_addr(ntohl(ctrl_data_in->data.ip_addr)); +            //new_addr["addr"] = ip_addr.to_string(); +            new_addr["addr"] = udp_transport->get_recv_addr(); + +            //Attempt a simple 2-way communication with a connected socket. +            //Reason: Although the USRP will respond the broadcast above, +            //we may not be able to communicate directly (non-broadcast). +            udp_simple::sptr ctrl_xport = udp_simple::make_connected( +                new_addr["addr"], BOOST_STRINGIZE(USRP2_UDP_CTRL_PORT) +            ); +            ctrl_xport->send(boost::asio::buffer(&ctrl_data_out, sizeof(ctrl_data_out))); +            size_t len = ctrl_xport->recv(asio::buffer(usrp2_ctrl_data_in_mem)); +            if (len > offsetof(usrp2_ctrl_data_t, data) and ntohl(ctrl_data_in->id) == USRP2_CTRL_ID_WAZZUP_DUDE){ +                //found the device, open up for communication! +            } +            else{ +                //otherwise we don't find it... +                continue; +            } + +            //Attempt to read the name from the EEPROM and perform filtering. +            //This operation can throw due to compatibility mismatch. +            try{ +                usrp2_iface::sptr iface = usrp2_iface::make(ctrl_xport); +                if (iface->is_device_locked()) continue; //ignore locked devices +                mboard_eeprom_t mb_eeprom = iface->mb_eeprom; +                new_addr["name"] = mb_eeprom["name"]; +                new_addr["serial"] = mb_eeprom["serial"]; +            } +            catch(const std::exception &){ +                //set these values as empty string so the device may still be found +                //and the filter's below can still operate on the discovered device +                new_addr["name"] = ""; +                new_addr["serial"] = ""; +            } + +            //filter the discovered device below by matching optional keys +            if ( +                (not hint.has_key("name")   or hint["name"]   == new_addr["name"]) and +                (not hint.has_key("serial") or hint["serial"] == new_addr["serial"]) +            ){ +                usrp2_addrs.push_back(new_addr); +            } + +            //dont break here, it will exit the while loop +            //just continue on to the next loop iteration +        } +        if (len == 0) break; //timeout +    } + +    return usrp2_addrs; +} + +/*********************************************************************** + * Make + **********************************************************************/ +static device::sptr usrp2_make(const device_addr_t &device_addr){ +    return device::sptr(new usrp2_impl(device_addr)); +} + +UHD_STATIC_BLOCK(register_usrp2_device){ +    device::register_device(&usrp2_find, &usrp2_make); +} + +/*********************************************************************** + * MTU Discovery + **********************************************************************/ +struct mtu_result_t{ +    size_t recv_mtu, send_mtu; +}; + +static mtu_result_t determine_mtu(const std::string &addr, const mtu_result_t &user_mtu){ +    udp_simple::sptr udp_sock = udp_simple::make_connected( +        addr, BOOST_STRINGIZE(USRP2_UDP_CTRL_PORT) +    ); + +    //The FPGA offers 4K buffers, and the user may manually request this. +    //However, multiple simultaneous receives (2DSP slave + 2DSP master), +    //require that buffering to be used internally, and this is a safe setting. +    std::vector<boost::uint8_t> buffer(std::max(user_mtu.recv_mtu, user_mtu.send_mtu)); +    usrp2_ctrl_data_t *ctrl_data = reinterpret_cast<usrp2_ctrl_data_t *>(&buffer.front()); +    static const double echo_timeout = 0.020; //20 ms + +    //test holler - check if its supported in this fw version +    ctrl_data->id = htonl(USRP2_CTRL_ID_HOLLER_AT_ME_BRO); +    ctrl_data->proto_ver = htonl(USRP2_FW_COMPAT_NUM); +    ctrl_data->data.echo_args.len = htonl(sizeof(usrp2_ctrl_data_t)); +    udp_sock->send(boost::asio::buffer(buffer, sizeof(usrp2_ctrl_data_t))); +    udp_sock->recv(boost::asio::buffer(buffer), echo_timeout); +    if (ntohl(ctrl_data->id) != USRP2_CTRL_ID_HOLLER_BACK_DUDE) +        throw uhd::not_implemented_error("holler protocol not implemented"); + +    size_t min_recv_mtu = sizeof(usrp2_ctrl_data_t), max_recv_mtu = user_mtu.recv_mtu; +    size_t min_send_mtu = sizeof(usrp2_ctrl_data_t), max_send_mtu = user_mtu.send_mtu; + +    while (min_recv_mtu < max_recv_mtu){ + +        size_t test_mtu = (max_recv_mtu/2 + min_recv_mtu/2 + 3) & ~3; + +        ctrl_data->id = htonl(USRP2_CTRL_ID_HOLLER_AT_ME_BRO); +        ctrl_data->proto_ver = htonl(USRP2_FW_COMPAT_NUM); +        ctrl_data->data.echo_args.len = htonl(test_mtu); +        udp_sock->send(boost::asio::buffer(buffer, sizeof(usrp2_ctrl_data_t))); + +        size_t len = udp_sock->recv(boost::asio::buffer(buffer), echo_timeout); + +        if (len >= test_mtu) min_recv_mtu = test_mtu; +        else                 max_recv_mtu = test_mtu - 4; + +    } + +    while (min_send_mtu < max_send_mtu){ + +        size_t test_mtu = (max_send_mtu/2 + min_send_mtu/2 + 3) & ~3; + +        ctrl_data->id = htonl(USRP2_CTRL_ID_HOLLER_AT_ME_BRO); +        ctrl_data->proto_ver = htonl(USRP2_FW_COMPAT_NUM); +        ctrl_data->data.echo_args.len = htonl(sizeof(usrp2_ctrl_data_t)); +        udp_sock->send(boost::asio::buffer(buffer, test_mtu)); + +        size_t len = udp_sock->recv(boost::asio::buffer(buffer), echo_timeout); +        if (len >= sizeof(usrp2_ctrl_data_t)) len = ntohl(ctrl_data->data.echo_args.len); + +        if (len >= test_mtu) min_send_mtu = test_mtu; +        else                 max_send_mtu = test_mtu - 4; +    } + +    mtu_result_t mtu; +    mtu.recv_mtu = min_recv_mtu; +    mtu.send_mtu = min_send_mtu; +    return mtu; +} + +/*********************************************************************** + * Helpers + **********************************************************************/ +static zero_copy_if::sptr make_xport( +    const std::string &addr, +    const std::string &port, +    const device_addr_t &hints, +    const std::string &filter +){ + +    //only copy hints that contain the filter word +    device_addr_t filtered_hints; +    BOOST_FOREACH(const std::string &key, hints.keys()){ +        if (key.find(filter) == std::string::npos) continue; +        filtered_hints[key] = hints[key]; +    } + +    //make the transport object with the filtered hints +    zero_copy_if::sptr xport = udp_zero_copy::make(addr, port, filtered_hints); + +    //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)); + +    return xport; +} + +/*********************************************************************** + * Structors + **********************************************************************/ +usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){ +    UHD_MSG(status) << "Opening a USRP2/N-Series device..." << std::endl; +    device_addr_t device_addr = _device_addr; + +    //setup the dsp transport hints (default to a large recv buff) +    if (not device_addr.has_key("recv_buff_size")){ +        #if defined(UHD_PLATFORM_MACOS) || defined(UHD_PLATFORM_BSD) +            //limit buffer resize on macos or it will error +            device_addr["recv_buff_size"] = "1e6"; +        #elif defined(UHD_PLATFORM_LINUX) || defined(UHD_PLATFORM_WIN32) +            //set to half-a-second of buffering at max rate +            device_addr["recv_buff_size"] = "50e6"; +        #endif +    } +    if (not device_addr.has_key("send_buff_size")){ +        //The buffer should be the size of the SRAM on the device, +        //because we will never commit more than the SRAM can hold. +        device_addr["send_buff_size"] = boost::lexical_cast<std::string>(USRP2_SRAM_BYTES); +    } + +    device_addrs_t device_args = separate_device_addr(device_addr); + +    //extract the user's requested MTU size or default +    mtu_result_t user_mtu; +    user_mtu.recv_mtu = size_t(device_addr.cast<double>("recv_frame_size", udp_simple::mtu)); +    user_mtu.send_mtu = size_t(device_addr.cast<double>("send_frame_size", udp_simple::mtu)); + +    try{ +        //calculate the minimum send and recv mtu of all devices +        mtu_result_t mtu = determine_mtu(device_args[0]["addr"], user_mtu); +        for (size_t i = 1; i < device_args.size(); i++){ +            mtu_result_t mtu_i = determine_mtu(device_args[i]["addr"], user_mtu); +            mtu.recv_mtu = std::min(mtu.recv_mtu, mtu_i.recv_mtu); +            mtu.send_mtu = std::min(mtu.send_mtu, mtu_i.send_mtu); +        } + +        device_addr["recv_frame_size"] = boost::lexical_cast<std::string>(mtu.recv_mtu); +        device_addr["send_frame_size"] = boost::lexical_cast<std::string>(mtu.send_mtu); + +        UHD_MSG(status) << boost::format("Current recv frame size: %d bytes") % mtu.recv_mtu << std::endl; +        UHD_MSG(status) << boost::format("Current send frame size: %d bytes") % mtu.send_mtu << std::endl; +    } +    catch(const uhd::not_implemented_error &){ +        //just ignore this error, makes older fw work... +    } + +    device_args = separate_device_addr(device_addr); //update args for new frame sizes + +    //////////////////////////////////////////////////////////////////// +    // 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 fs_path mb_path = "/mboards/" + mb; + +        //////////////////////////////////////////////////////////////// +        // 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()); +        _tree->create<std::string>(mb_path / "fw_version").set(_mbc[mb].iface->get_fw_version_string()); + +        //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.\n" +                "%s\n" +            ) % int(USRP2_FPGA_COMPAT_NUM) % fpga_major % _mbc[mb].iface->images_warn_help_message())); +        } +        _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); + +        //////////////////////////////////////////////////////////////// +        // construct transports for RX and TX DSPs +        //////////////////////////////////////////////////////////////// +        UHD_LOG << "Making transport for RX DSP0..." << std::endl; +        _mbc[mb].rx_dsp_xports.push_back(make_xport( +            addr, BOOST_STRINGIZE(USRP2_UDP_RX_DSP0_PORT), device_args_i, "recv" +        )); +        UHD_LOG << "Making transport for RX DSP1..." << std::endl; +        _mbc[mb].rx_dsp_xports.push_back(make_xport( +            addr, BOOST_STRINGIZE(USRP2_UDP_RX_DSP1_PORT), device_args_i, "recv" +        )); +        UHD_LOG << "Making transport for TX DSP0..." << std::endl; +        _mbc[mb].tx_dsp_xport = make_xport( +            addr, BOOST_STRINGIZE(USRP2_UDP_TX_DSP0_PORT), device_args_i, "send" +        ); +        UHD_LOG << "Making transport for Control..." << std::endl; +        _mbc[mb].fifo_ctrl_xport = make_xport( +            addr, BOOST_STRINGIZE(USRP2_UDP_FIFO_CRTL_PORT), device_addr_t(), "" +        ); +        //set the filter on the router to take dsp data from this port +        _mbc[mb].iface->poke32(U2_REG_ROUTER_CTRL_PORTS, (USRP2_UDP_FIFO_CRTL_PORT << 16) | USRP2_UDP_TX_DSP0_PORT); + +        //create the fifo control interface for high speed register access +        _mbc[mb].fifo_ctrl = usrp2_fifo_ctrl::make(_mbc[mb].fifo_ctrl_xport); +        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].wbiface = _mbc[mb].fifo_ctrl; +            _mbc[mb].spiface = _mbc[mb].fifo_ctrl; +            break; +        default: +            _mbc[mb].wbiface = _mbc[mb].iface; +            _mbc[mb].spiface = _mbc[mb].iface; +            break; +        } + +        //////////////////////////////////////////////////////////////// +        // 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, _mbc[mb].spiface); +        _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 fs_path rx_codec_path = mb_path / "rx_codecs/A"; +        const fs_path 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, _mbc[mb].spiface); +        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 the GPSDO control +        //////////////////////////////////////////////////////////////////// +        static const boost::uint32_t dont_look_for_gpsdo = 0x1234abcdul; + +        //disable check for internal GPSDO when not the following: +        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: +            break; +        default: +            _mbc[mb].iface->pokefw(U2_FW_REG_HAS_GPSDO, dont_look_for_gpsdo); +        } + +        //otherwise if not disabled, look for the internal GPSDO +        if (_mbc[mb].iface->peekfw(U2_FW_REG_HAS_GPSDO) != dont_look_for_gpsdo) +        { +            UHD_MSG(status) << "Detecting internal GPSDO.... " << std::flush; +            try{ +                _mbc[mb].gps = gps_ctrl::make(udp_simple::make_uart(udp_simple::make_connected( +                    addr, BOOST_STRINGIZE(USRP2_UDP_UART_GPS_PORT) +                ))); +            } +            catch(std::exception &e){ +                UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl; +            } +            if (_mbc[mb].gps and _mbc[mb].gps->gps_detected()) +            { +                UHD_MSG(status) << "found" << std::endl; +                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)); +                } +            } +            else +            { +                UHD_MSG(status) << "not found" << std::endl; +                _mbc[mb].iface->pokefw(U2_FW_REG_HAS_GPSDO, dont_look_for_gpsdo); +            } +        } + +        //////////////////////////////////////////////////////////////// +        // 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].wbiface, U2_REG_SR_ADDR(SR_RX_FRONT) +        ); +        _mbc[mb].tx_fe = tx_frontend_core_200::make( +            _mbc[mb].wbiface, U2_REG_SR_ADDR(SR_TX_FRONT) +        ); + +        _tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec") +            .subscribe(boost::bind(&usrp2_impl::update_rx_subdev_spec, this, mb, _1)); +        _tree->create<subdev_spec_t>(mb_path / "tx_subdev_spec") +            .subscribe(boost::bind(&usrp2_impl::update_tx_subdev_spec, this, mb, _1)); + +        const fs_path rx_fe_path = mb_path / "rx_frontends" / "A"; +        const fs_path tx_fe_path = mb_path / "tx_frontends" / "A"; + +        _tree->create<std::complex<double> >(rx_fe_path / "dc_offset" / "value") +            .coerce(boost::bind(&rx_frontend_core_200::set_dc_offset, _mbc[mb].rx_fe, _1)) +            .set(std::complex<double>(0.0, 0.0)); +        _tree->create<bool>(rx_fe_path / "dc_offset" / "enable") +            .subscribe(boost::bind(&rx_frontend_core_200::set_dc_offset_auto, _mbc[mb].rx_fe, _1)) +            .set(true); +        _tree->create<std::complex<double> >(rx_fe_path / "iq_balance" / "value") +            .subscribe(boost::bind(&rx_frontend_core_200::set_iq_balance, _mbc[mb].rx_fe, _1)) +            .set(std::complex<double>(0.0, 0.0)); +        _tree->create<std::complex<double> >(tx_fe_path / "dc_offset" / "value") +            .coerce(boost::bind(&tx_frontend_core_200::set_dc_offset, _mbc[mb].tx_fe, _1)) +            .set(std::complex<double>(0.0, 0.0)); +        _tree->create<std::complex<double> >(tx_fe_path / "iq_balance" / "value") +            .subscribe(boost::bind(&tx_frontend_core_200::set_iq_balance, _mbc[mb].tx_fe, _1)) +            .set(std::complex<double>(0.0, 0.0)); + +        //////////////////////////////////////////////////////////////// +        // create rx dsp control objects +        //////////////////////////////////////////////////////////////// +        _mbc[mb].rx_dsps.push_back(rx_dsp_core_200::make( +            _mbc[mb].wbiface, 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].wbiface, U2_REG_SR_ADDR(SR_RX_DSP1), U2_REG_SR_ADDR(SR_RX_CTRL1), USRP2_RX_SID_BASE + 1, true +        )); +        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)); +            fs_path rx_dsp_path = mb_path / str(boost::format("rx_dsps/%u") % dspno); +            _tree->create<meta_range_t>(rx_dsp_path / "rate/range") +                .publish(boost::bind(&rx_dsp_core_200::get_host_rates, _mbc[mb].rx_dsps[dspno])); +            _tree->create<double>(rx_dsp_path / "rate/value") +                .set(1e6) //some default +                .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, mb, dspno, _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].wbiface, 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<meta_range_t>(mb_path / "tx_dsps/0/rate/range") +            .publish(boost::bind(&tx_dsp_core_200::get_host_rates, _mbc[mb].tx_dsp)); +        _tree->create<double>(mb_path / "tx_dsps/0/rate/value") +            .set(1e6) //some default +            .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, mb, 0, _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].tx_dsp_xport->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_hi_now = U2_REG_TIME64_HI_RB_IMM; +        time64_rb_bases.rb_lo_now = U2_REG_TIME64_LO_RB_IMM; +        time64_rb_bases.rb_hi_pps = U2_REG_TIME64_HI_RB_PPS; +        time64_rb_bases.rb_lo_pps = U2_REG_TIME64_LO_RB_PPS; +        _mbc[mb].time64 = time64_core_200::make( +            _mbc[mb].wbiface, 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)); +        std::vector<std::string> clock_sources = boost::assign::list_of("internal")("external")("mimo"); +        if (_mbc[mb].gps and _mbc[mb].gps->gps_detected()) clock_sources.push_back("gpsdo"); +        _tree->create<std::vector<std::string> >(mb_path / "clock_source/options").set(clock_sources); +        //plug timed commands into tree here +        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<time_spec_t>(mb_path / "time/cmd") +                .subscribe(boost::bind(&usrp2_fifo_ctrl::set_time, _mbc[mb].fifo_ctrl, _1)); +        default: break; //otherwise, do not register +        } +        _tree->access<double>(mb_path / "tick_rate") +            .subscribe(boost::bind(&usrp2_fifo_ctrl::set_tick_rate, _mbc[mb].fifo_ctrl, _1)); + +        //////////////////////////////////////////////////////////////////// +        // create user-defined control objects +        //////////////////////////////////////////////////////////////////// +        _mbc[mb].user = user_settings_core_200::make(_mbc[mb].wbiface, U2_REG_SR_ADDR(SR_USER_REGS)); +        _tree->create<user_settings_core_200::user_reg_t>(mb_path / "user/regs") +            .subscribe(boost::bind(&user_settings_core_200::set_reg, _mbc[mb].user, _1)); + +        //////////////////////////////////////////////////////////////// +        // 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].wbiface, _mbc[mb].iface/*i2c*/, _mbc[mb].spiface, _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, tx_db_eeprom.id, gdb_eeprom.id, +            _mbc[mb].dboard_iface, _tree->subtree(mb_path / "dboards/A") +        ); + +        //bind frontend corrections to the dboard freq props +        const fs_path db_tx_fe_path = mb_path / "dboards" / "A" / "tx_frontends"; +        BOOST_FOREACH(const std::string &name, _tree->list(db_tx_fe_path)){ +            _tree->access<double>(db_tx_fe_path / name / "freq" / "value") +                .subscribe(boost::bind(&usrp2_impl::set_tx_fe_corrections, this, mb, _1)); +        } +        const fs_path db_rx_fe_path = mb_path / "dboards" / "A" / "rx_frontends"; +        BOOST_FOREACH(const std::string &name, _tree->list(db_rx_fe_path)){ +            _tree->access<double>(db_rx_fe_path / name / "freq" / "value") +                .subscribe(boost::bind(&usrp2_impl::set_rx_fe_corrections, this, mb, _1)); +        } +    } + +    //initialize io handling +    this->io_init(); + +    //do some post-init tasks +    this->update_rates(); +    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        fs_path root = "/mboards/" + mb; + +        //reset cordic rates and their properties to zero +        BOOST_FOREACH(const std::string &name, _tree->list(root / "rx_dsps")){ +            _tree->access<double>(root / "rx_dsps" / name / "freq" / "value").set(0.0); +        } +        BOOST_FOREACH(const std::string &name, _tree->list(root / "tx_dsps")){ +            _tree->access<double>(root / "tx_dsps" / name / "freq" / "value").set(0.0); +        } + +        _tree->access<subdev_spec_t>(root / "rx_subdev_spec").set(subdev_spec_t("A:" + _tree->list(root / "dboards/A/rx_frontends").at(0))); +        _tree->access<subdev_spec_t>(root / "tx_subdev_spec").set(subdev_spec_t("A:" + _tree->list(root / "dboards/A/tx_frontends").at(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 and _mbc[mb].gps->gps_detected()){ +            _mbc[mb].time64->enable_gpsdo(); +            UHD_MSG(status) << "Setting references to the internal GPSDO" << std::endl; +            _tree->access<std::string>(root / "time_source/value").set("gpsdo"); +            _tree->access<std::string>(root / "clock_source/value").set("gpsdo"); +            UHD_MSG(status) << "Initializing time to the internal GPSDO" << std::endl; +            _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){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), USRP2_EEPROM_MAP_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); +} + +sensor_value_t usrp2_impl::get_mimo_locked(const std::string &mb){ +    const bool lock = (_mbc[mb].wbiface->peek32(U2_REG_IRQ_RB) & (1<<10)) != 0; +    return sensor_value_t("MIMO", lock, "locked", "unlocked"); +} + +sensor_value_t usrp2_impl::get_ref_locked(const std::string &mb){ +    const bool lock = (_mbc[mb].wbiface->peek32(U2_REG_IRQ_RB) & (1<<11)) != 0; +    return sensor_value_t("Ref", lock, "locked", "unlocked"); +} + +void usrp2_impl::set_rx_fe_corrections(const std::string &mb, const double lo_freq){ +    apply_rx_fe_corrections(this->get_tree()->subtree("/mboards/" + mb), "A", lo_freq); +} + +void usrp2_impl::set_tx_fe_corrections(const std::string &mb, const double lo_freq){ +    apply_tx_fe_corrections(this->get_tree()->subtree("/mboards/" + mb), "A", lo_freq); +} + +#include <boost/math/special_functions/round.hpp> +#include <boost/math/special_functions/sign.hpp> + +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 +} + +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){ +    //NOTICE: U2_REG_MISC_CTRL_CLOCK is on the wb clock, and cannot be set from fifo_ctrl +    //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 == "gpsdo")     _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 new file mode 100644 index 000000000..a6c0d87cf --- /dev/null +++ b/host/lib/usrp/usrp2/usrp2_impl.hpp @@ -0,0 +1,139 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_USRP2_IMPL_HPP +#define INCLUDED_USRP2_IMPL_HPP + +#include "gpio_core_200.hpp" +#include "usrp2_iface.hpp" +#include "usrp2_fifo_ctrl.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 "user_settings_core_200.hpp" +#include <uhd/property_tree.hpp> +#include <uhd/usrp/gps_ctrl.hpp> +#include <uhd/device.hpp> +#include <uhd/utils/pimpl.hpp> +#include <uhd/types/dict.hpp> +#include <uhd/types/stream_cmd.hpp> +#include <uhd/types/clock_config.hpp> +#include <uhd/usrp/dboard_eeprom.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/function.hpp> +#include <uhd/transport/vrt_if_packet.hpp> +#include <uhd/transport/udp_simple.hpp> +#include <uhd/transport/udp_zero_copy.hpp> +#include <uhd/usrp/dboard_manager.hpp> +#include <uhd/usrp/subdev_spec.hpp> +#include <boost/weak_ptr.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 = 4.10e-9; +static const size_t mimo_clock_sync_delay_cycles = 138; +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; +static const std::string USRP2_EEPROM_MAP_KEY = "N100"; + +//! Make a usrp2 dboard interface. +uhd::usrp::dboard_iface::sptr make_usrp2_dboard_iface( +    wb_iface::sptr wb_iface, +    uhd::i2c_iface::sptr i2c_iface, +    uhd::spi_iface::sptr spi_iface, +    usrp2_clock_ctrl::sptr clk_ctrl +); + +/*! + * USRP2 implementation guts: + * The implementation details are encapsulated here. + * Handles device properties and streaming... + */ +class usrp2_impl : public uhd::device{ +public: +    usrp2_impl(const uhd::device_addr_t &); +    ~usrp2_impl(void); + +    //the io interface +    uhd::rx_streamer::sptr get_rx_stream(const uhd::stream_args_t &args); +    uhd::tx_streamer::sptr get_tx_stream(const uhd::stream_args_t &args); +    bool recv_async_msg(uhd::async_metadata_t &, double); + +private: +    uhd::property_tree::sptr _tree; +    struct mb_container_type{ +        usrp2_iface::sptr iface; +        usrp2_fifo_ctrl::sptr fifo_ctrl; +        uhd::spi_iface::sptr spiface; +        wb_iface::sptr wbiface; +        usrp2_clock_ctrl::sptr clock; +        usrp2_codec_ctrl::sptr codec; +        uhd::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; +        std::vector<boost::weak_ptr<uhd::rx_streamer> > rx_streamers; +        std::vector<boost::weak_ptr<uhd::tx_streamer> > tx_streamers; +        tx_dsp_core_200::sptr tx_dsp; +        time64_core_200::sptr time64; +        user_settings_core_200::sptr user; +        std::vector<uhd::transport::zero_copy_if::sptr> rx_dsp_xports; +        uhd::transport::zero_copy_if::sptr tx_dsp_xport; +        uhd::transport::zero_copy_if::sptr fifo_ctrl_xport; +        uhd::usrp::dboard_manager::sptr dboard_manager; +        uhd::usrp::dboard_iface::sptr dboard_iface; +        size_t rx_chan_occ, tx_chan_occ; +        mb_container_type(void): rx_chan_occ(0), tx_chan_occ(0){} +    }; +    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 &); + +    void set_rx_fe_corrections(const std::string &mb, const double); +    void set_tx_fe_corrections(const std::string &mb, const double); + +    //device properties interface +    uhd::property_tree::sptr get_tree(void) const{ +        return _tree; +    } + +    //io impl methods and members +    UHD_PIMPL_DECL(io_impl) _io_impl; +    void io_init(void); +    void update_tick_rate(const double rate); +    void update_rx_samp_rate(const std::string &, const size_t, const double rate); +    void update_tx_samp_rate(const std::string &, const size_t, const double rate); +    void update_rates(void); +    //update spec methods are coercers until we only accept db_name == A +    void update_rx_subdev_spec(const std::string &, const uhd::usrp::subdev_spec_t &); +    void 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 &); +    void program_stream_dest(uhd::transport::zero_copy_if::sptr &, const uhd::stream_args_t &); +}; + +#endif /* INCLUDED_USRP2_IMPL_HPP */ diff --git a/host/lib/usrp/usrp2/usrp2_regs.hpp b/host/lib/usrp/usrp2/usrp2_regs.hpp new file mode 100644 index 000000000..7fe83e709 --- /dev/null +++ b/host/lib/usrp/usrp2/usrp2_regs.hpp @@ -0,0 +1,107 @@ +// +// Copyright 2010-2012 Ettus Research LLC +// +// This program is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program.  If not, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_USRP2_REGS_HPP +#define INCLUDED_USRP2_REGS_HPP + +//////////////////////////////////////////////////////////////////////// +// Define slave bases +//////////////////////////////////////////////////////////////////////// +#define ROUTER_RAM_BASE     0x4000 +#define SPI_BASE            0x5000 +#define I2C_BASE            0x5400 +#define GPIO_BASE           0x5800 +#define READBACK_BASE       0x5C00 +#define ETH_BASE            0x6000 +#define SETTING_REGS_BASE   0x7000 +#define PIC_BASE            0x8000 +#define UART_BASE           0x8800 +#define ATR_BASE            0x8C00 + +//////////////////////////////////////////////////////////////////////// +// Setting register offsets +//////////////////////////////////////////////////////////////////////// +#define SR_MISC       0   // 7 regs +#define SR_USER_REGS  8   // 2 +#define SR_TIME64    10   // 6 +#define SR_BUF_POOL  16   // 4 +#define SR_SPI_CORE  20   // 3 +#define SR_RX_FRONT  24   // 5 +#define SR_RX_CTRL0  32   // 9 +#define SR_RX_DSP0   48   // 7 +#define SR_RX_CTRL1  80   // 9 +#define SR_RX_DSP1   96   // 7 + +#define SR_TX_FRONT 128   // ? +#define SR_TX_CTRL  144   // 6 +#define SR_TX_DSP   160   // 5 + +#define SR_GPIO     184 +#define SR_UDP_SM   192   // 64 + +#define U2_REG_SR_ADDR(sr) (SETTING_REGS_BASE + (4 * (sr))) + +#define U2_REG_ROUTER_CTRL_PORTS U2_REG_SR_ADDR(SR_BUF_POOL) + 8 + +///////////////////////////////////////////////// +// SPI Slave Constants +//////////////////////////////////////////////// +// Masks for controlling different peripherals +#define SPI_SS_AD9510    1 +#define SPI_SS_AD9777    2 +#define SPI_SS_RX_DAC    4 +#define SPI_SS_RX_ADC    8 +#define SPI_SS_RX_DB    16 +#define SPI_SS_TX_DAC   32 +#define SPI_SS_TX_ADC   64 +#define SPI_SS_TX_DB   128 +#define SPI_SS_ADS62P44 256 //for usrp2p + +///////////////////////////////////////////////// +// Misc Control +//////////////////////////////////////////////// +#define U2_REG_MISC_CTRL_CLOCK U2_REG_SR_ADDR(0) +#define U2_REG_MISC_CTRL_SERDES U2_REG_SR_ADDR(1) +#define U2_REG_MISC_CTRL_ADC U2_REG_SR_ADDR(2) +#define U2_REG_MISC_CTRL_LEDS U2_REG_SR_ADDR(3) +#define U2_REG_MISC_CTRL_PHY U2_REG_SR_ADDR(4) +#define U2_REG_MISC_CTRL_DBG_MUX U2_REG_SR_ADDR(5) +#define U2_REG_MISC_CTRL_RAM_PAGE U2_REG_SR_ADDR(6) +#define U2_REG_MISC_CTRL_FLUSH_ICACHE U2_REG_SR_ADDR(7) +#define U2_REG_MISC_CTRL_LED_SRC U2_REG_SR_ADDR(8) + +#define U2_FLAG_MISC_CTRL_SERDES_ENABLE 8 +#define U2_FLAG_MISC_CTRL_SERDES_PRBSEN 4 +#define U2_FLAG_MISC_CTRL_SERDES_LOOPEN 2 +#define U2_FLAG_MISC_CTRL_SERDES_RXEN   1 + +#define U2_FLAG_MISC_CTRL_ADC_ON  0x0F +#define U2_FLAG_MISC_CTRL_ADC_OFF 0x00 + +///////////////////////////////////////////////// +// Readback regs +//////////////////////////////////////////////// +#define U2_REG_STATUS READBACK_BASE + 4*8 +#define U2_REG_GPIO_RB READBACK_BASE + 4*9 +#define U2_REG_TIME64_HI_RB_IMM READBACK_BASE + 4*10 +#define U2_REG_TIME64_LO_RB_IMM READBACK_BASE + 4*11 +#define U2_REG_COMPAT_NUM_RB READBACK_BASE + 4*12 +#define U2_REG_IRQ_RB READBACK_BASE + 4*13 +#define U2_REG_TIME64_HI_RB_PPS READBACK_BASE + 4*14 +#define U2_REG_TIME64_LO_RB_PPS READBACK_BASE + 4*15 + +#endif /* INCLUDED_USRP2_REGS_HPP */  | 
