aboutsummaryrefslogtreecommitdiffstats
path: root/host/lib/usrp
diff options
context:
space:
mode:
Diffstat (limited to 'host/lib/usrp')
-rw-r--r--host/lib/usrp/b100/CMakeLists.txt3
-rw-r--r--host/lib/usrp/b100/b100_ctrl.cpp257
-rw-r--r--host/lib/usrp/b100/b100_ctrl.hpp70
-rw-r--r--host/lib/usrp/b100/b100_impl.cpp132
-rw-r--r--host/lib/usrp/b100/b100_impl.hpp31
-rw-r--r--host/lib/usrp/b100/b100_regs.hpp116
-rw-r--r--host/lib/usrp/b100/ctrl_packet.hpp75
-rw-r--r--host/lib/usrp/b100/dboard_iface.cpp2
-rw-r--r--host/lib/usrp/b100/io_impl.cpp71
-rw-r--r--host/lib/usrp/common/CMakeLists.txt3
-rw-r--r--host/lib/usrp/common/apply_corrections.cpp12
-rw-r--r--host/lib/usrp/common/fifo_ctrl_excelsior.cpp293
-rw-r--r--host/lib/usrp/common/fifo_ctrl_excelsior.hpp63
-rw-r--r--host/lib/usrp/common/fx2_ctrl.cpp39
-rw-r--r--host/lib/usrp/cores/CMakeLists.txt1
-rw-r--r--host/lib/usrp/cores/gpio_core_200.cpp8
-rw-r--r--host/lib/usrp/cores/i2c_core_200.cpp158
-rw-r--r--host/lib/usrp/cores/i2c_core_200.hpp35
-rw-r--r--host/lib/usrp/cores/rx_dsp_core_200.cpp21
-rw-r--r--host/lib/usrp/cores/time64_core_200.cpp6
-rw-r--r--host/lib/usrp/cores/time64_core_200.hpp4
-rw-r--r--host/lib/usrp/cores/tx_dsp_core_200.cpp9
-rw-r--r--host/lib/usrp/dboard/db_basic_and_lf.cpp30
-rw-r--r--host/lib/usrp/dboard/db_dbsrx.cpp2
-rw-r--r--host/lib/usrp/dboard/db_dbsrx2.cpp4
-rw-r--r--host/lib/usrp/dboard/db_rfx.cpp24
-rw-r--r--host/lib/usrp/dboard/db_sbx_common.cpp34
-rw-r--r--host/lib/usrp/dboard/db_sbx_common.hpp3
-rw-r--r--host/lib/usrp/dboard/db_sbx_version3.cpp25
-rw-r--r--host/lib/usrp/dboard/db_sbx_version4.cpp23
-rw-r--r--host/lib/usrp/dboard/db_tvrx.cpp4
-rw-r--r--host/lib/usrp/dboard/db_tvrx2.cpp4
-rw-r--r--host/lib/usrp/dboard/db_wbx_common.cpp3
-rw-r--r--host/lib/usrp/dboard/db_wbx_simple.cpp9
-rw-r--r--host/lib/usrp/dboard/db_wbx_version2.cpp34
-rw-r--r--host/lib/usrp/dboard/db_wbx_version3.cpp34
-rw-r--r--host/lib/usrp/dboard/db_wbx_version4.cpp32
-rw-r--r--host/lib/usrp/dboard/db_xcvr2450.cpp4
-rw-r--r--host/lib/usrp/e100/dboard_iface.cpp2
-rw-r--r--host/lib/usrp/e100/e100_ctrl.cpp166
-rw-r--r--host/lib/usrp/e100/e100_ctrl.hpp9
-rw-r--r--host/lib/usrp/e100/e100_impl.cpp188
-rw-r--r--host/lib/usrp/e100/e100_impl.hpp23
-rw-r--r--host/lib/usrp/e100/e100_mmap_zero_copy.cpp45
-rw-r--r--host/lib/usrp/e100/e100_regs.hpp130
-rw-r--r--host/lib/usrp/e100/include/linux/usrp_e.h4
-rw-r--r--host/lib/usrp/e100/io_impl.cpp143
-rw-r--r--host/lib/usrp/mboard_eeprom.cpp101
-rw-r--r--host/lib/usrp/multi_usrp.cpp96
-rw-r--r--host/lib/usrp/usrp1/codec_ctrl.cpp9
-rw-r--r--host/lib/usrp/usrp1/io_impl.cpp12
-rw-r--r--host/lib/usrp/usrp1/usrp1_impl.cpp28
-rw-r--r--host/lib/usrp/usrp1/usrp1_impl.hpp4
-rw-r--r--host/lib/usrp/usrp2/CMakeLists.txt3
-rw-r--r--host/lib/usrp/usrp2/clock_ctrl.cpp13
-rw-r--r--host/lib/usrp/usrp2/clock_ctrl.hpp7
-rw-r--r--host/lib/usrp/usrp2/codec_ctrl.cpp14
-rw-r--r--host/lib/usrp/usrp2/codec_ctrl.hpp7
-rw-r--r--host/lib/usrp/usrp2/dboard_iface.cpp48
-rw-r--r--host/lib/usrp/usrp2/fw_common.h19
-rw-r--r--host/lib/usrp/usrp2/io_impl.cpp58
-rw-r--r--host/lib/usrp/usrp2/usrp2_fifo_ctrl.cpp244
-rw-r--r--host/lib/usrp/usrp2/usrp2_fifo_ctrl.hpp47
-rw-r--r--host/lib/usrp/usrp2/usrp2_iface.cpp100
-rw-r--r--host/lib/usrp/usrp2/usrp2_iface.hpp11
-rw-r--r--host/lib/usrp/usrp2/usrp2_impl.cpp131
-rw-r--r--host/lib/usrp/usrp2/usrp2_impl.hpp19
-rw-r--r--host/lib/usrp/usrp2/usrp2_regs.hpp4
68 files changed, 2073 insertions, 1290 deletions
diff --git a/host/lib/usrp/b100/CMakeLists.txt b/host/lib/usrp/b100/CMakeLists.txt
index 1237f52d1..d2c33b512 100644
--- a/host/lib/usrp/b100/CMakeLists.txt
+++ b/host/lib/usrp/b100/CMakeLists.txt
@@ -1,5 +1,5 @@
#
-# Copyright 2011 Ettus Research LLC
+# Copyright 2011-2012 Ettus Research LLC
#
# This program is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
@@ -26,7 +26,6 @@ LIBUHD_REGISTER_COMPONENT("B100" ENABLE_B100 ON "ENABLE_LIBUHD;ENABLE_USB" OFF)
IF(ENABLE_B100)
LIBUHD_APPEND_SOURCES(
- ${CMAKE_CURRENT_SOURCE_DIR}/b100_ctrl.cpp
${CMAKE_CURRENT_SOURCE_DIR}/b100_impl.cpp
${CMAKE_CURRENT_SOURCE_DIR}/clock_ctrl.cpp
${CMAKE_CURRENT_SOURCE_DIR}/codec_ctrl.cpp
diff --git a/host/lib/usrp/b100/b100_ctrl.cpp b/host/lib/usrp/b100/b100_ctrl.cpp
deleted file mode 100644
index e6136c00e..000000000
--- a/host/lib/usrp/b100/b100_ctrl.cpp
+++ /dev/null
@@ -1,257 +0,0 @@
-//
-// Copyright 2011 Ettus Research LLC
-//
-// This program is free software: you can redistribute it and/or modify
-// it under the terms of the GNU General Public License as published by
-// the Free Software Foundation, either version 3 of the License, or
-// (at your option) any later version.
-//
-// This program is distributed in the hope that it will be useful,
-// but WITHOUT ANY WARRANTY; without even the implied warranty of
-// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
-// GNU General Public License for more details.
-//
-// You should have received a copy of the GNU General Public License
-// along with this program. If not, see <http://www.gnu.org/licenses/>.
-//
-
-#include "b100_ctrl.hpp"
-#include <uhd/transport/bounded_buffer.hpp>
-#include <uhd/transport/usb_zero_copy.hpp>
-#include <uhd/transport/zero_copy.hpp>
-#include <uhd/transport/vrt_if_packet.hpp>
-#include <uhd/utils/thread_priority.hpp>
-#include <uhd/utils/msg.hpp>
-#include <uhd/utils/tasks.hpp>
-#include <uhd/types/metadata.hpp>
-#include <uhd/types/serial.hpp>
-#include "ctrl_packet.hpp"
-#include <boost/thread/thread.hpp>
-#include <boost/bind.hpp>
-#include <uhd/exception.hpp>
-
-using namespace uhd::transport;
-using namespace uhd;
-
-bool b100_ctrl_debug = false;
-
-class b100_ctrl_impl : public b100_ctrl {
-public:
- b100_ctrl_impl(uhd::transport::zero_copy_if::sptr ctrl_transport):
- sync_ctrl_fifo(2),
- _ctrl_transport(ctrl_transport),
- _seq(0)
- {
- viking_marauder = task::make(boost::bind(&b100_ctrl_impl::viking_marauder_loop, this));
- }
-
- ~b100_ctrl_impl(void){
- //stop the marauder first so it cant access deconstructed objects
- viking_marauder.reset();
- }
-
- int write(boost::uint32_t addr, const ctrl_data_t &data);
- ctrl_data_t read(boost::uint32_t addr, size_t len);
-
- bool get_ctrl_data(ctrl_data_t &pkt_data, double timeout);
-
- void poke32(wb_addr_type addr, boost::uint32_t data){
- boost::mutex::scoped_lock lock(_ctrl_mutex);
-
- ctrl_data_t words(2);
- words[0] = data & 0x0000FFFF;
- words[1] = data >> 16;
- this->write(addr, words);
- }
-
- boost::uint32_t peek32(wb_addr_type addr){
- boost::mutex::scoped_lock lock(_ctrl_mutex);
-
- ctrl_data_t words = this->read(addr, 2);
- return boost::uint32_t((boost::uint32_t(words[1]) << 16) | words[0]);
- }
-
- void poke16(wb_addr_type addr, boost::uint16_t data){
- boost::mutex::scoped_lock lock(_ctrl_mutex);
-
- ctrl_data_t words(1);
- words[0] = data;
- this->write(addr, words);
- }
-
- boost::uint16_t peek16(wb_addr_type addr){
- boost::mutex::scoped_lock lock(_ctrl_mutex);
-
- ctrl_data_t words = this->read(addr, 1);
- return boost::uint16_t(words[0]);
- }
-
- void set_async_cb(const async_cb_type &async_cb){
- boost::mutex::scoped_lock lock(_async_mutex);
- _async_cb = async_cb;
- }
-
-private:
- int send_pkt(boost::uint16_t *cmd);
-
- //änd hërë wë gö ä-Vïkïng för äsynchronous control packets
- void viking_marauder_loop(void);
- bounded_buffer<ctrl_data_t> sync_ctrl_fifo;
- async_cb_type _async_cb;
- task::sptr viking_marauder;
-
- uhd::transport::zero_copy_if::sptr _ctrl_transport;
- boost::uint8_t _seq;
- boost::mutex _ctrl_mutex, _async_mutex;
-};
-
-/***********************************************************************
- * helper functions for packing/unpacking control packets
- **********************************************************************/
-void pack_ctrl_pkt(boost::uint16_t *pkt_buff,
- const ctrl_pkt_t &pkt){
- //first two bits are OP
- //next six bits are CALLBACKS
- //next 8 bits are SEQUENCE
- //next 16 bits are LENGTH (16-bit word)
- //next 32 bits are ADDRESS (16-bit word LSW)
- //then DATA (28 16-bit words)
- pkt_buff[0] = (boost::uint16_t(pkt.pkt_meta.op) << 14) | (boost::uint16_t(pkt.pkt_meta.callbacks) << 8) | pkt.pkt_meta.seq;
- pkt_buff[1] = pkt.pkt_meta.len;
- pkt_buff[2] = (pkt.pkt_meta.addr & 0x00000FFF);
- pkt_buff[3] = 0x0000; //address high bits always 0 on this device
-
- for(size_t i = 0; i < pkt.data.size(); i++) {
- pkt_buff[4+i] = pkt.data[i];
- }
-}
-
-void unpack_ctrl_pkt(const boost::uint16_t *pkt_buff,
- ctrl_pkt_t &pkt){
- pkt.pkt_meta.seq = pkt_buff[0] & 0xFF;
- pkt.pkt_meta.op = CTRL_PKT_OP_READ; //really this is useless
- pkt.pkt_meta.len = pkt_buff[1];
- pkt.pkt_meta.callbacks = 0; //callbacks aren't implemented yet
- pkt.pkt_meta.addr = pkt_buff[2] | boost::uint32_t(pkt_buff[3] << 16);
-
- //let's check this so we don't go pushing 64K of crap onto the pkt
- if(pkt.pkt_meta.len > CTRL_PACKET_DATA_LENGTH) {
- throw uhd::runtime_error("Received control packet too long");
- }
-
- for(int i = 4; i < 4+pkt.pkt_meta.len; i++) pkt.data.push_back(pkt_buff[i]);
-}
-
-int b100_ctrl_impl::send_pkt(boost::uint16_t *cmd) {
- managed_send_buffer::sptr sbuf = _ctrl_transport->get_send_buff();
- if(!sbuf.get()) {
- throw uhd::runtime_error("Control channel send error");
- }
-
- //FIXME there's a better way to do this
- for(size_t i = 0; i < (CTRL_PACKET_LENGTH / sizeof(boost::uint16_t)); i++) {
- sbuf->cast<boost::uint16_t *>()[i] = cmd[i];
- }
- sbuf->commit(CTRL_PACKET_LENGTH); //fixed size transaction
- return 0;
-}
-
-int b100_ctrl_impl::write(boost::uint32_t addr, const ctrl_data_t &data) {
- UHD_ASSERT_THROW(data.size() <= (CTRL_PACKET_DATA_LENGTH / sizeof(boost::uint16_t)));
- ctrl_pkt_t pkt;
- pkt.data = data;
- pkt.pkt_meta.op = CTRL_PKT_OP_WRITE;
- pkt.pkt_meta.callbacks = 0;
- pkt.pkt_meta.seq = _seq++;
- pkt.pkt_meta.len = pkt.data.size();
- pkt.pkt_meta.addr = addr;
- boost::uint16_t pkt_buff[CTRL_PACKET_LENGTH / sizeof(boost::uint16_t)] = {};
-
- pack_ctrl_pkt(pkt_buff, pkt);
- size_t result = send_pkt(pkt_buff);
- return result;
-}
-
-ctrl_data_t b100_ctrl_impl::read(boost::uint32_t addr, size_t len) {
- UHD_ASSERT_THROW(len <= (CTRL_PACKET_DATA_LENGTH / sizeof(boost::uint16_t)));
-
- ctrl_pkt_t pkt;
- pkt.pkt_meta.op = CTRL_PKT_OP_READ;
- pkt.pkt_meta.callbacks = 0;
- pkt.pkt_meta.seq = _seq++;
- pkt.pkt_meta.len = len;
- pkt.pkt_meta.addr = addr;
- boost::uint16_t pkt_buff[CTRL_PACKET_LENGTH / sizeof(boost::uint16_t)] = {};
-
- //flush anything that might be in the queue
- while (get_ctrl_data(pkt.data, 0.0)){
- UHD_MSG(error) << "B100: control read found unexpected packet." << std::endl;
- }
-
- pack_ctrl_pkt(pkt_buff, pkt);
- send_pkt(pkt_buff);
-
- //block with timeout waiting for the response to appear
- if (not get_ctrl_data(pkt.data, 0.1)) throw uhd::runtime_error(
- "B100: timeout waiting for control response packet."
- );
-
- return pkt.data;
-}
-
-/***********************************************************************
- * Viking marauders go pillaging for asynchronous control packets in the
- * control response endpoint. Sync packets go in sync_ctrl_fifo,
- * async TX error messages go in async_msg_fifo. sync_ctrl_fifo should
- * never have more than 1 message in it, since it's expected that we'll
- * wait for a control operation to finish before starting another one.
- **********************************************************************/
-void b100_ctrl_impl::viking_marauder_loop(void){
- set_thread_priority_safe();
-
- while (not boost::this_thread::interruption_requested()){
- managed_recv_buffer::sptr rbuf = _ctrl_transport->get_recv_buff(1.0);
- if(rbuf.get() == NULL) continue; //that's ok, there are plenty of villages to pillage!
- const boost::uint16_t *pkt_buf = rbuf->cast<const boost::uint16_t *>();
-
- if(pkt_buf[0] >> 8 == CTRL_PACKET_HEADER_MAGIC) {
- //so it's got a control packet header, let's parse it.
- ctrl_pkt_t pkt;
- unpack_ctrl_pkt(pkt_buf, pkt);
-
- if(pkt.pkt_meta.seq != boost::uint8_t(_seq - 1)) {
- UHD_MSG(error)
- << "Sequence error on control channel." << std::endl
- << "Exiting control loop." << std::endl
- ;
- return;
- }
- if(pkt.pkt_meta.len > (CTRL_PACKET_LENGTH - CTRL_PACKET_HEADER_LENGTH)) {
- UHD_MSG(error)
- << "Control channel packet length too long" << std::endl
- << "Exiting control loop." << std::endl
- ;
- return;
- }
-
- //push it onto the queue
- sync_ctrl_fifo.push_with_pop_on_full(pkt.data);
- }
- else{ //otherwise let the async callback handle it
- boost::mutex::scoped_lock lock(_async_mutex);
- if (not _async_cb.empty()) _async_cb(rbuf);
- }
- }
-}
-
-bool b100_ctrl_impl::get_ctrl_data(ctrl_data_t &pkt_data, double timeout){
- boost::this_thread::disable_interruption di; //disable because the wait can throw
- return sync_ctrl_fifo.pop_with_timed_wait(pkt_data, timeout);
-}
-
-/***********************************************************************
- * Public make function for b100_ctrl interface
- **********************************************************************/
-b100_ctrl::sptr b100_ctrl::make(uhd::transport::zero_copy_if::sptr ctrl_transport){
- return sptr(new b100_ctrl_impl(ctrl_transport));
-}
diff --git a/host/lib/usrp/b100/b100_ctrl.hpp b/host/lib/usrp/b100/b100_ctrl.hpp
deleted file mode 100644
index 74884d525..000000000
--- a/host/lib/usrp/b100/b100_ctrl.hpp
+++ /dev/null
@@ -1,70 +0,0 @@
-//
-// Copyright 2011 Ettus Research LLC
-//
-// This program is free software: you can redistribute it and/or modify
-// it under the terms of the GNU General Public License as published by
-// the Free Software Foundation, either version 3 of the License, or
-// (at your option) any later version.
-//
-// This program is distributed in the hope that it will be useful,
-// but WITHOUT ANY WARRANTY; without even the implied warranty of
-// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
-// GNU General Public License for more details.
-//
-// You should have received a copy of the GNU General Public License
-// along with this program. If not, see <http://www.gnu.org/licenses/>.
-//
-
-#ifndef INCLUDED_B100_CTRL_HPP
-#define INCLUDED_B100_CTRL_HPP
-
-#include "wb_iface.hpp"
-#include <uhd/transport/usb_zero_copy.hpp>
-#include <uhd/types/serial.hpp>
-#include <boost/shared_ptr.hpp>
-#include <boost/utility.hpp>
-#include "ctrl_packet.hpp"
-#include <boost/function.hpp>
-
-class b100_ctrl : boost::noncopyable, public wb_iface{
-public:
- typedef boost::shared_ptr<b100_ctrl> sptr;
- typedef boost::function<void(uhd::transport::managed_recv_buffer::sptr)> async_cb_type;
-
- /*!
- * Make a USRP control object from a data transport
- * \param ctrl_transport a USB data transport
- * \return a new b100 control object
- */
- static sptr make(uhd::transport::zero_copy_if::sptr ctrl_transport);
-
- //! set an async callback for messages
- virtual void set_async_cb(const async_cb_type &async_cb) = 0;
-
- /*!
- * Write a byte vector to an FPGA register
- * \param addr the FPGA register address
- * \param bytes the data to write
- * \return 0 on success, error code on failure
- */
- virtual int write(boost::uint32_t addr, const ctrl_data_t &data) = 0;
-
- /*!
- * Read a byte vector from an FPGA register (blocking read)
- * \param addr the FPGA register address
- * \param len the length of the read
- * \return a vector of bytes from the register(s) in question
- */
- virtual ctrl_data_t read(boost::uint32_t addr, size_t len) = 0;
-
- /*!
- * Get a sync ctrl packet (blocking)
- * \param the packet data buffer
- * \param the timeout value
- * \return true if it got something
- */
- virtual bool get_ctrl_data(ctrl_data_t &pkt_data, double timeout) = 0;
-
-};
-
-#endif /* INCLUDED_B100_CTRL_HPP */
diff --git a/host/lib/usrp/b100/b100_impl.cpp b/host/lib/usrp/b100/b100_impl.cpp
index b1d9a577a..c4d050242 100644
--- a/host/lib/usrp/b100/b100_impl.cpp
+++ b/host/lib/usrp/b100/b100_impl.cpp
@@ -17,9 +17,8 @@
#include "apply_corrections.hpp"
#include "b100_impl.hpp"
-#include "b100_ctrl.hpp"
+#include "b100_regs.hpp"
#include <uhd/transport/usb_control.hpp>
-#include "ctrl_packet.hpp"
#include <uhd/utils/msg.hpp>
#include <uhd/exception.hpp>
#include <uhd/utils/static.hpp>
@@ -30,8 +29,8 @@
#include <boost/filesystem.hpp>
#include <boost/thread/thread.hpp>
#include <boost/lexical_cast.hpp>
-#include "b100_regs.hpp"
#include <cstdio>
+#include <iostream>
using namespace uhd;
using namespace uhd::usrp;
@@ -82,13 +81,10 @@ static device_addrs_t b100_find(const device_addr_t &hint)
b100_fw_image = find_image_path(hint.get("fw", B100_FW_FILE_NAME));
}
catch(...){
- UHD_MSG(warning) << boost::format(
- "Could not locate B100 firmware.\n"
- "Please install the images package.\n"
- );
+ UHD_MSG(warning) << boost::format("Could not locate B100 firmware. %s\n") % print_images_error();
return b100_addrs;
}
- UHD_LOG << "the firmware image: " << b100_fw_image << std::endl;
+ UHD_LOG << "the firmware image: " << b100_fw_image << std::endl;
usb_control::sptr control;
try{control = usb_control::make(handle, 0);}
@@ -114,7 +110,7 @@ static device_addrs_t b100_find(const device_addr_t &hint)
catch(const uhd::exception &){continue;} //ignore claimed
fx2_ctrl::sptr fx2_ctrl = fx2_ctrl::make(control);
- const mboard_eeprom_t mb_eeprom = mboard_eeprom_t(*fx2_ctrl, mboard_eeprom_t::MAP_B100);
+ const mboard_eeprom_t mb_eeprom = mboard_eeprom_t(*fx2_ctrl, B100_EEPROM_MAP_KEY);
device_addr_t new_addr;
new_addr["type"] = "b100";
new_addr["name"] = mb_eeprom["name"];
@@ -187,10 +183,10 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
//create the control transport
device_addr_t ctrl_xport_args;
- ctrl_xport_args["recv_frame_size"] = boost::lexical_cast<std::string>(CTRL_PACKET_LENGTH);
+ ctrl_xport_args["recv_frame_size"] = "512";
ctrl_xport_args["num_recv_frames"] = "16";
- ctrl_xport_args["send_frame_size"] = boost::lexical_cast<std::string>(CTRL_PACKET_LENGTH);
- ctrl_xport_args["num_send_frames"] = "4";
+ ctrl_xport_args["send_frame_size"] = "512";
+ ctrl_xport_args["num_send_frames"] = "16";
_ctrl_transport = usb_zero_copy::make(
handle,
@@ -198,17 +194,22 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
3, 4, //interface, endpoint
ctrl_xport_args
);
- while (_ctrl_transport->get_recv_buff(0.0)){} //flush ctrl xport
this->enable_gpif(true);
////////////////////////////////////////////////////////////////////
- // Initialize FPGA wishbone communication
+ // Initialize FPGA control communication
////////////////////////////////////////////////////////////////////
- _fpga_ctrl = b100_ctrl::make(_ctrl_transport);
- _fpga_ctrl->poke32(B100_REG_GLOBAL_RESET, 0); //global fpga reset
+ fifo_ctrl_excelsior_config fifo_ctrl_config;
+ fifo_ctrl_config.async_sid_base = B100_TX_ASYNC_SID;
+ fifo_ctrl_config.num_async_chan = 1;
+ fifo_ctrl_config.ctrl_sid_base = B100_CTRL_MSG_SID;
+ fifo_ctrl_config.spi_base = TOREG(SR_SPI);
+ fifo_ctrl_config.spi_rb = REG_RB_SPI;
+ _fifo_ctrl = fifo_ctrl_excelsior::make(_ctrl_transport, fifo_ctrl_config);
+
//perform a test peek operation
try{
- _fpga_ctrl->peek32(0);
+ _fifo_ctrl->peek32(0);
}
//try reset once in the case of failure
catch(const uhd::exception &){
@@ -216,7 +217,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
UHD_MSG(warning) <<
"The control endpoint was left in a bad state.\n"
"Attempting endpoint re-enumeration...\n" << std::endl;
- _fpga_ctrl.reset();
+ _fifo_ctrl.reset();
_ctrl_transport.reset();
_fx2_ctrl->usrp_fx2_reset();
goto b100_impl_constructor_begin;
@@ -226,8 +227,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
////////////////////////////////////////////////////////////////////
// Initialize peripherals after reset
////////////////////////////////////////////////////////////////////
- _fpga_i2c_ctrl = i2c_core_100::make(_fpga_ctrl, B100_REG_SLAVE(3));
- _fpga_spi_ctrl = spi_core_100::make(_fpga_ctrl, B100_REG_SLAVE(2));
+ _fpga_i2c_ctrl = i2c_core_200::make(_fifo_ctrl, TOREG(SR_I2C), REG_RB_I2C);
////////////////////////////////////////////////////////////////////
// Create data transport
@@ -241,6 +241,10 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
data_xport_args["send_frame_size"] = device_addr.get("send_frame_size", "16384");
data_xport_args["num_send_frames"] = device_addr.get("num_send_frames", "16");
+ //let packet padder know the LUT size in number of words32
+ const size_t rx_lut_size = size_t(data_xport_args.cast<double>("recv_frame_size", 0.0));
+ _fifo_ctrl->poke32(TOREG(SR_PADDER+0), rx_lut_size/sizeof(boost::uint32_t));
+
_data_transport = usb_zero_copy::make_wrapper(
usb_zero_copy::make(
handle, // identifier
@@ -250,21 +254,21 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
),
B100_MAX_PKT_BYTE_LIMIT
);
- while (_data_transport->get_recv_buff(0.0)){} //flush data xport
////////////////////////////////////////////////////////////////////
// Initialize the properties tree
////////////////////////////////////////////////////////////////////
_tree->create<std::string>("/name").set("B-Series Device");
const fs_path mb_path = "/mboards/0";
- _tree->create<std::string>(mb_path / "name").set("B100 (B-Hundo)");
+ _tree->create<std::string>(mb_path / "name").set("B100");
+ _tree->create<std::string>(mb_path / "codename").set("B-Hundo");
_tree->create<std::string>(mb_path / "load_eeprom")
.subscribe(boost::bind(&fx2_ctrl::usrp_load_eeprom, _fx2_ctrl, _1));
////////////////////////////////////////////////////////////////////
// setup the mboard eeprom
////////////////////////////////////////////////////////////////////
- const mboard_eeprom_t mb_eeprom(*_fx2_ctrl, mboard_eeprom_t::MAP_B100);
+ const mboard_eeprom_t mb_eeprom(*_fx2_ctrl, B100_EEPROM_MAP_KEY);
_tree->create<mboard_eeprom_t>(mb_path / "eeprom")
.set(mb_eeprom)
.subscribe(boost::bind(&b100_impl::set_mb_eeprom, this, _1));
@@ -275,12 +279,17 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
//^^^ clock created up top, just reg props here... ^^^
_tree->create<double>(mb_path / "tick_rate")
.publish(boost::bind(&b100_clock_ctrl::get_fpga_clock_rate, _clock_ctrl))
+ .subscribe(boost::bind(&fifo_ctrl_excelsior::set_tick_rate, _fifo_ctrl, _1))
.subscribe(boost::bind(&b100_impl::update_tick_rate, this, _1));
+ //subscribe the command time while we are at it
+ _tree->create<time_spec_t>(mb_path / "time/cmd")
+ .subscribe(boost::bind(&fifo_ctrl_excelsior::set_time, _fifo_ctrl, _1));
+
////////////////////////////////////////////////////////////////////
// create codec control objects
////////////////////////////////////////////////////////////////////
- _codec_ctrl = b100_codec_ctrl::make(_fpga_spi_ctrl);
+ _codec_ctrl = b100_codec_ctrl::make(_fifo_ctrl);
const fs_path rx_codec_path = mb_path / "rx_codecs/A";
const fs_path tx_codec_path = mb_path / "tx_codecs/A";
_tree->create<std::string>(rx_codec_path / "name").set("ad9522");
@@ -302,8 +311,8 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
////////////////////////////////////////////////////////////////////
// create frontend control objects
////////////////////////////////////////////////////////////////////
- _rx_fe = rx_frontend_core_200::make(_fpga_ctrl, B100_REG_SR_ADDR(B100_SR_RX_FRONT));
- _tx_fe = tx_frontend_core_200::make(_fpga_ctrl, B100_REG_SR_ADDR(B100_SR_TX_FRONT));
+ _rx_fe = rx_frontend_core_200::make(_fifo_ctrl, TOREG(SR_RX_FE));
+ _tx_fe = tx_frontend_core_200::make(_fifo_ctrl, TOREG(SR_TX_FE));
_tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec")
.subscribe(boost::bind(&b100_impl::update_rx_subdev_spec, this, _1));
@@ -332,13 +341,17 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
////////////////////////////////////////////////////////////////////
// create rx dsp control objects
////////////////////////////////////////////////////////////////////
- _rx_dsps.push_back(rx_dsp_core_200::make(
- _fpga_ctrl, B100_REG_SR_ADDR(B100_SR_RX_DSP0), B100_REG_SR_ADDR(B100_SR_RX_CTRL0), B100_RX_SID_BASE + 0
- ));
- _rx_dsps.push_back(rx_dsp_core_200::make(
- _fpga_ctrl, B100_REG_SR_ADDR(B100_SR_RX_DSP1), B100_REG_SR_ADDR(B100_SR_RX_CTRL1), B100_RX_SID_BASE + 1
- ));
- for (size_t dspno = 0; dspno < _rx_dsps.size(); dspno++){
+ const size_t num_rx_dsps = _fifo_ctrl->peek32(REG_RB_NUM_RX_DSP);
+ for (size_t dspno = 0; dspno < num_rx_dsps; dspno++)
+ {
+ const size_t sr_off = dspno*32;
+ _rx_dsps.push_back(rx_dsp_core_200::make(
+ _fifo_ctrl,
+ TOREG(SR_RX_DSP0+sr_off),
+ TOREG(SR_RX_CTRL0+sr_off),
+ B100_RX_SID_BASE + dspno
+ ));
+
_rx_dsps[dspno]->set_link_rate(B100_LINK_RATE_BPS);
_tree->access<double>(mb_path / "tick_rate")
.subscribe(boost::bind(&rx_dsp_core_200::set_tick_rate, _rx_dsps[dspno], _1));
@@ -361,7 +374,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
// create tx dsp control objects
////////////////////////////////////////////////////////////////////
_tx_dsp = tx_dsp_core_200::make(
- _fpga_ctrl, B100_REG_SR_ADDR(B100_SR_TX_DSP), B100_REG_SR_ADDR(B100_SR_TX_CTRL), B100_TX_ASYNC_SID
+ _fifo_ctrl, TOREG(SR_TX_DSP), TOREG(SR_TX_CTRL), B100_TX_ASYNC_SID
);
_tx_dsp->set_link_rate(B100_LINK_RATE_BPS);
_tree->access<double>(mb_path / "tick_rate")
@@ -381,12 +394,12 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
// create time control objects
////////////////////////////////////////////////////////////////////
time64_core_200::readback_bases_type time64_rb_bases;
- time64_rb_bases.rb_hi_now = B100_REG_RB_TIME_NOW_HI;
- time64_rb_bases.rb_lo_now = B100_REG_RB_TIME_NOW_LO;
- time64_rb_bases.rb_hi_pps = B100_REG_RB_TIME_PPS_HI;
- time64_rb_bases.rb_lo_pps = B100_REG_RB_TIME_PPS_LO;
+ time64_rb_bases.rb_hi_now = REG_RB_TIME_NOW_HI;
+ time64_rb_bases.rb_lo_now = REG_RB_TIME_NOW_LO;
+ time64_rb_bases.rb_hi_pps = REG_RB_TIME_PPS_HI;
+ time64_rb_bases.rb_lo_pps = REG_RB_TIME_PPS_LO;
_time64 = time64_core_200::make(
- _fpga_ctrl, B100_REG_SR_ADDR(B100_SR_TIME64), time64_rb_bases
+ _fifo_ctrl, TOREG(SR_TIME64), time64_rb_bases
);
_tree->access<double>(mb_path / "tick_rate")
.subscribe(boost::bind(&time64_core_200::set_tick_rate, _time64, _1));
@@ -410,7 +423,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
////////////////////////////////////////////////////////////////////
// create user-defined control objects
////////////////////////////////////////////////////////////////////
- _user = user_settings_core_200::make(_fpga_ctrl, B100_REG_SR_ADDR(B100_SR_USER_REGS));
+ _user = user_settings_core_200::make(_fifo_ctrl, TOREG(SR_USER_REGS));
_tree->create<user_settings_core_200::user_reg_t>(mb_path / "user/regs")
.subscribe(boost::bind(&user_settings_core_200::set_reg, _user, _1));
@@ -424,6 +437,9 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
tx_db_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_TX_A);
gdb_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_TX_A ^ 5);
+ //disable rx dc offset if LFRX
+ if (rx_db_eeprom.id == 0x000f) _tree->access<bool>(rx_fe_path / "dc_offset" / "enable").set(false);
+
//create the properties and register subscribers
_tree->create<dboard_eeprom_t>(mb_path / "dboards/A/rx_eeprom")
.set(rx_db_eeprom)
@@ -436,7 +452,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
.subscribe(boost::bind(&b100_impl::set_db_eeprom, this, "gdb", _1));
//create a new dboard interface and manager
- _dboard_iface = make_b100_dboard_iface(_fpga_ctrl, _fpga_i2c_ctrl, _fpga_spi_ctrl, _clock_ctrl, _codec_ctrl);
+ _dboard_iface = make_b100_dboard_iface(_fifo_ctrl, _fpga_i2c_ctrl, _fifo_ctrl/*spi*/, _clock_ctrl, _codec_ctrl);
_tree->create<dboard_iface::sptr>(mb_path / "dboards/A/iface").set(_dboard_iface);
_dboard_manager = dboard_manager::make(
rx_db_eeprom.id, tx_db_eeprom.id, gdb_eeprom.id,
@@ -456,7 +472,11 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
}
//initialize io handling
- this->io_init();
+ _recv_demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), B100_RX_SID_BASE);
+
+ //allocate streamer weak ptrs containers
+ _rx_streamers.resize(_rx_dsps.size());
+ _tx_streamers.resize(1/*known to be 1 dsp*/);
////////////////////////////////////////////////////////////////////
// do some post-init tasks
@@ -481,8 +501,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){
}
b100_impl::~b100_impl(void){
- //set an empty async callback now that we deconstruct
- _fpga_ctrl->set_async_cb(b100_ctrl::async_cb_type());
+ //NOP
}
void b100_impl::check_fw_compat(void){
@@ -493,13 +512,14 @@ void b100_impl::check_fw_compat(void){
if (fw_compat_num != B100_FW_COMPAT_NUM){
throw uhd::runtime_error(str(boost::format(
"Expected firmware compatibility number 0x%x, but got 0x%x:\n"
- "The firmware build is not compatible with the host code build."
- ) % B100_FW_COMPAT_NUM % fw_compat_num));
+ "The firmware build is not compatible with the host code build.\n"
+ "%s"
+ ) % B100_FW_COMPAT_NUM % fw_compat_num % print_images_error()));
}
}
void b100_impl::check_fpga_compat(void){
- const boost::uint32_t fpga_compat_num = _fpga_ctrl->peek32(B100_REG_RB_COMPAT);
+ const boost::uint32_t fpga_compat_num = _fifo_ctrl->peek32(REG_RB_COMPAT);
boost::uint16_t fpga_major = fpga_compat_num >> 16, fpga_minor = fpga_compat_num & 0xffff;
if (fpga_major == 0){ //old version scheme
fpga_major = fpga_minor;
@@ -509,7 +529,8 @@ void b100_impl::check_fpga_compat(void){
throw uhd::runtime_error(str(boost::format(
"Expected FPGA compatibility number %d, but got %d:\n"
"The FPGA build is not compatible with the host code build."
- ) % int(B100_FPGA_COMPAT_NUM) % fpga_major));
+ "%s"
+ ) % int(B100_FPGA_COMPAT_NUM) % fpga_major % print_images_error()));
}
_tree->create<std::string>("/mboards/0/fpga_version").set(str(boost::format("%u.%u") % fpga_major % fpga_minor));
}
@@ -523,7 +544,7 @@ double b100_impl::update_rx_codec_gain(const double gain){
}
void b100_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){
- mb_eeprom.commit(*_fx2_ctrl, mboard_eeprom_t::MAP_B100);
+ mb_eeprom.commit(*_fx2_ctrl, B100_EEPROM_MAP_KEY);
}
void b100_impl::set_db_eeprom(const std::string &type, const uhd::usrp::dboard_eeprom_t &db_eeprom){
@@ -533,6 +554,19 @@ void b100_impl::set_db_eeprom(const std::string &type, const uhd::usrp::dboard_e
}
void b100_impl::update_clock_source(const std::string &source){
+
+ if (source == "pps_sync"){
+ _clock_ctrl->use_external_ref();
+ _fifo_ctrl->poke32(TOREG(SR_MISC+2), 1);
+ return;
+ }
+ if (source == "_pps_sync_"){
+ _clock_ctrl->use_external_ref();
+ _fifo_ctrl->poke32(TOREG(SR_MISC+2), 3);
+ return;
+ }
+ _fifo_ctrl->poke32(TOREG(SR_MISC+2), 0);
+
if (source == "auto") _clock_ctrl->use_auto_ref();
else if (source == "internal") _clock_ctrl->use_internal_ref();
else if (source == "external") _clock_ctrl->use_external_ref();
diff --git a/host/lib/usrp/b100/b100_impl.hpp b/host/lib/usrp/b100/b100_impl.hpp
index 82d5a5f53..68d7043a1 100644
--- a/host/lib/usrp/b100/b100_impl.hpp
+++ b/host/lib/usrp/b100/b100_impl.hpp
@@ -19,20 +19,19 @@
#define INCLUDED_B100_IMPL_HPP
#include "fx2_ctrl.hpp"
-#include "b100_ctrl.hpp"
#include "clock_ctrl.hpp"
#include "codec_ctrl.hpp"
-#include "spi_core_100.hpp"
-#include "i2c_core_100.hpp"
+#include "i2c_core_200.hpp"
#include "rx_frontend_core_200.hpp"
#include "tx_frontend_core_200.hpp"
#include "rx_dsp_core_200.hpp"
#include "tx_dsp_core_200.hpp"
#include "time64_core_200.hpp"
+#include "fifo_ctrl_excelsior.hpp"
#include "user_settings_core_200.hpp"
+#include "recv_packet_demuxer.hpp"
#include <uhd/device.hpp>
#include <uhd/property_tree.hpp>
-#include <uhd/utils/pimpl.hpp>
#include <uhd/types/dict.hpp>
#include <uhd/types/sensors.hpp>
#include <uhd/types/clock_config.hpp>
@@ -47,12 +46,14 @@
static const double B100_LINK_RATE_BPS = 256e6/5; //pratical link rate (< 480 Mbps)
static const std::string B100_FW_FILE_NAME = "usrp_b100_fw.ihx";
static const std::string B100_FPGA_FILE_NAME = "usrp_b100_fpga.bin";
-static const boost::uint16_t B100_FW_COMPAT_NUM = 0x03;
-static const boost::uint16_t B100_FPGA_COMPAT_NUM = 0x09;
-static const boost::uint32_t B100_RX_SID_BASE = 2;
-static const boost::uint32_t B100_TX_ASYNC_SID = 1;
+static const boost::uint16_t B100_FW_COMPAT_NUM = 0x04;
+static const boost::uint16_t B100_FPGA_COMPAT_NUM = 11;
+static const boost::uint32_t B100_RX_SID_BASE = 30;
+static const boost::uint32_t B100_TX_ASYNC_SID = 10;
+static const boost::uint32_t B100_CTRL_MSG_SID = 20;
static const double B100_DEFAULT_TICK_RATE = 64e6;
static const size_t B100_MAX_PKT_BYTE_LIMIT = 2048;
+static const std::string B100_EEPROM_MAP_KEY = "B100";
#define I2C_ADDR_TX_A (I2C_DEV_EEPROM | 0x4)
#define I2C_ADDR_RX_A (I2C_DEV_EEPROM | 0x5)
@@ -89,8 +90,8 @@ private:
uhd::property_tree::sptr _tree;
//controllers
- spi_core_100::sptr _fpga_spi_ctrl;
- i2c_core_100::sptr _fpga_i2c_ctrl;
+ fifo_ctrl_excelsior::sptr _fifo_ctrl;
+ i2c_core_200::sptr _fpga_i2c_ctrl;
rx_frontend_core_200::sptr _rx_fe;
tx_frontend_core_200::sptr _tx_fe;
std::vector<rx_dsp_core_200::sptr> _rx_dsps;
@@ -99,20 +100,17 @@ private:
user_settings_core_200::sptr _user;
b100_clock_ctrl::sptr _clock_ctrl;
b100_codec_ctrl::sptr _codec_ctrl;
- b100_ctrl::sptr _fpga_ctrl;
uhd::usrp::fx2_ctrl::sptr _fx2_ctrl;
//transports
- uhd::transport::zero_copy_if::sptr _data_transport, _ctrl_transport;
+ uhd::transport::zero_copy_if::sptr _ctrl_transport;
+ uhd::transport::zero_copy_if::sptr _data_transport;
+ uhd::usrp::recv_packet_demuxer::sptr _recv_demuxer;
//dboard stuff
uhd::usrp::dboard_manager::sptr _dboard_manager;
uhd::usrp::dboard_iface::sptr _dboard_iface;
- //handle io stuff
- UHD_PIMPL_DECL(io_impl) _io_impl;
- void io_init(void);
-
//device properties interface
uhd::property_tree::sptr get_tree(void) const{
return _tree;
@@ -135,7 +133,6 @@ private:
void update_clock_source(const std::string &);
void enable_gpif(const bool);
void clear_fpga_fifo(void);
- void handle_async_message(uhd::transport::managed_recv_buffer::sptr);
uhd::sensor_value_t get_ref_locked(void);
void set_rx_fe_corrections(const double);
void set_tx_fe_corrections(const double);
diff --git a/host/lib/usrp/b100/b100_regs.hpp b/host/lib/usrp/b100/b100_regs.hpp
index 987a09f03..48eb0460d 100644
--- a/host/lib/usrp/b100/b100_regs.hpp
+++ b/host/lib/usrp/b100/b100_regs.hpp
@@ -15,109 +15,49 @@
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
-////////////////////////////////////////////////////////////////
-//
-// Memory map for wishbone bus
-//
-////////////////////////////////////////////////////////////////
-
-// All addresses are byte addresses. All accesses are word (16-bit) accesses.
-// This means that address bit 0 is usually 0.
-// There are 11 bits of address for the control.
-
#ifndef INCLUDED_B100_REGS_HPP
#define INCLUDED_B100_REGS_HPP
-/////////////////////////////////////////////////////
-// Slave pointers
+#include <boost/cstdint.hpp>
-#define B100_REG_SLAVE(n) ((n)<<7)
+#define TOREG(x) ((x)*4)
-/////////////////////////////////////////////////////
-// Slave 0 -- Misc Regs
+#define localparam static const int
-#define B100_REG_MISC_BASE B100_REG_SLAVE(0)
+localparam SR_MISC = 0; // 5
+localparam SR_USER_REGS = 5; // 2
+localparam SR_PADDER = 10; // 2
-#define B100_REG_MISC_LED B100_REG_MISC_BASE + 0
-#define B100_REG_MISC_SW B100_REG_MISC_BASE + 2
-#define B100_REG_MISC_CGEN_CTRL B100_REG_MISC_BASE + 4
-#define B100_REG_MISC_CGEN_ST B100_REG_MISC_BASE + 6
+localparam SR_TX_CTRL = 32; // 6
+localparam SR_TX_DSP = 40; // 5
+localparam SR_TX_FE = 48; // 5
-/////////////////////////////////////////////////////
-// Slave 1 -- UART
-// CLKDIV is 16 bits, others are only 8
+localparam SR_RX_CTRL0 = 96; // 9
+localparam SR_RX_DSP0 = 106; // 7
+localparam SR_RX_FE = 114; // 5
-#define B100_REG_UART_BASE B100_REG_SLAVE(1)
+localparam SR_RX_CTRL1 = 128; // 9
+localparam SR_RX_DSP1 = 138; // 7
-#define B100_REG_UART_CLKDIV B100_REG_UART_BASE + 0
-#define B100_REG_UART_TXLEVEL B100_REG_UART_BASE + 2
-#define B100_REG_UART_RXLEVEL B100_REG_UART_BASE + 4
-#define B100_REG_UART_TXCHAR B100_REG_UART_BASE + 6
-#define B100_REG_UART_RXCHAR B100_REG_UART_BASE + 8
+localparam SR_TIME64 = 192; // 6
+localparam SR_SPI = 208; // 3
+localparam SR_I2C = 216; // 1
+localparam SR_GPIO = 224; // 5
-/////////////////////////////////////////////////////
-// Slave 2 -- SPI Core
-//these are 32-bit registers mapped onto the 16-bit Wishbone bus.
-//Using peek32/poke32 should allow transparent use of these registers.
-#define B100_REG_SPI_BASE B100_REG_SLAVE(2)
+#define REG_RB_TIME_NOW_HI TOREG(10)
+#define REG_RB_TIME_NOW_LO TOREG(11)
+#define REG_RB_TIME_PPS_HI TOREG(14)
+#define REG_RB_TIME_PPS_LO TOREG(15)
+#define REG_RB_SPI TOREG(0)
+#define REG_RB_COMPAT TOREG(1)
+#define REG_RB_GPIO TOREG(3)
+#define REG_RB_I2C TOREG(2)
+#define REG_RB_NUM_RX_DSP TOREG(6)
//spi slave constants
#define B100_SPI_SS_AD9862 (1 << 2)
#define B100_SPI_SS_TX_DB (1 << 1)
#define B100_SPI_SS_RX_DB (1 << 0)
-////////////////////////////////////////////////
-// Slave 3 -- I2C Core
-
-#define B100_REG_I2C_BASE B100_REG_SLAVE(3)
-
-///////////////////////////////////////////////////
-// Slave 7 -- Readback Mux 32
-
-#define B100_REG_RB_MUX_32_BASE B100_REG_SLAVE(7)
-
-#define B100_REG_RB_TIME_NOW_HI B100_REG_RB_MUX_32_BASE + 0
-#define B100_REG_RB_TIME_NOW_LO B100_REG_RB_MUX_32_BASE + 4
-#define B100_REG_RB_TIME_PPS_HI B100_REG_RB_MUX_32_BASE + 8
-#define B100_REG_RB_TIME_PPS_LO B100_REG_RB_MUX_32_BASE + 12
-#define B100_REG_RB_MISC_TEST32 B100_REG_RB_MUX_32_BASE + 16
-#define B100_REG_RB_COMPAT B100_REG_RB_MUX_32_BASE + 24
-#define B100_REG_RB_GPIO B100_REG_RB_MUX_32_BASE + 28
-
-////////////////////////////////////////////////////
-// Slaves 8 & 9 -- Settings Bus
-//
-// Output-only, no readback, 64 registers total
-// Each register must be written 32 bits at a time
-// First the address xxx_xx00 and then xxx_xx10
-// 64 total regs in address space
-#define B100_SR_RX_CTRL0 0 // 9 regs (+0 to +8)
-#define B100_SR_RX_DSP0 10 // 4 regs (+0 to +3)
-#define B100_SR_RX_CTRL1 16 // 9 regs (+0 to +8)
-#define B100_SR_RX_DSP1 26 // 4 regs (+0 to +3)
-#define B100_SR_TX_CTRL 32 // 4 regs (+0 to +3)
-#define B100_SR_TX_DSP 38 // 3 regs (+0 to +2)
-
-#define B100_SR_TIME64 42 // 6 regs (+0 to +5)
-#define B100_SR_RX_FRONT 48 // 5 regs (+0 to +4)
-#define B100_SR_TX_FRONT 54 // 5 regs (+0 to +4)
-
-#define B100_SR_REG_TEST32 60 // 1 reg
-#define B100_SR_CLEAR_FIFO 61 // 1 reg
-#define B100_SR_GLOBAL_RESET 63 // 1 reg
-#define B100_SR_USER_REGS 64 // 2 regs
-
-#define B100_SR_GPIO 128
-
-#define B100_REG_SR_ADDR(n) (B100_REG_SLAVE(8) + (4*(n)))
-
-#define B100_REG_SR_MISC_TEST32 B100_REG_SR_ADDR(B100_SR_REG_TEST32)
-
-/////////////////////////////////////////////////
-// Magic reset regs
-////////////////////////////////////////////////
-#define B100_REG_CLEAR_FIFO B100_REG_SR_ADDR(B100_SR_CLEAR_FIFO)
-#define B100_REG_GLOBAL_RESET B100_REG_SR_ADDR(B100_SR_GLOBAL_RESET)
-
-#endif
+#endif /*INCLUDED_B100_REGS_HPP*/
diff --git a/host/lib/usrp/b100/ctrl_packet.hpp b/host/lib/usrp/b100/ctrl_packet.hpp
deleted file mode 100644
index bab1f0de1..000000000
--- a/host/lib/usrp/b100/ctrl_packet.hpp
+++ /dev/null
@@ -1,75 +0,0 @@
-//
-// Copyright 2011 Ettus Research LLC
-//
-// This program is free software: you can redistribute it and/or modify
-// it under the terms of the GNU General Public License as published by
-// the Free Software Foundation, either version 3 of the License, or
-// (at your option) any later version.
-//
-// This program is distributed in the hope that it will be useful,
-// but WITHOUT ANY WARRANTY; without even the implied warranty of
-// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
-// GNU General Public License for more details.
-//
-// You should have received a copy of the GNU General Public License
-// along with this program. If not, see <http://www.gnu.org/licenses/>.
-//
-
-#ifndef INCLUDED_CTRL_PACKET_HPP
-#define INCLUDED_CTRL_PACKET_HPP
-
-#include <uhd/config.hpp>
-#include <boost/cstdint.hpp>
-#include <uhd/types/serial.hpp>
-
-typedef std::vector<boost::uint16_t> ctrl_data_t;
-
-/*!
- * Control packet operation type
- */
-enum ctrl_pkt_op_t {
- CTRL_PKT_OP_WRITE = 1,
- CTRL_PKT_OP_READ = 2,
- CTRL_PKT_OP_READBACK = 3
-};
-
-/*!
- * Control packet transaction length
- */
-const size_t CTRL_PACKET_LENGTH = 32;
-const size_t CTRL_PACKET_HEADER_LENGTH = 8;
-const size_t CTRL_PACKET_DATA_LENGTH = 24; //=length-header
-
-/*!
- * Control packet header magic value
- */
-const boost::uint8_t CTRL_PACKET_HEADER_MAGIC = 0xAA;
-
-/*!
- * Callback triggers for readback operation
- */
-//FIXME: these are not real numbers, callbacks aren't implemented yet
-const boost::uint16_t CTRL_PACKET_CALLBACK_SPI = 0x0001;
-const boost::uint16_t CTRL_PACKET_CALLBACK_I2C = 0x0002;
-//and so on
-
-/*!
- * Metadata structure to describe a control packet
- */
-struct UHD_API ctrl_pkt_meta_t {
- ctrl_pkt_op_t op;
- boost::uint8_t callbacks;
- boost::uint8_t seq;
- boost::uint16_t len;
- boost::uint32_t addr;
-};
-
-/*!
- * Full control packet structure
- */
-struct UHD_API ctrl_pkt_t {
- ctrl_pkt_meta_t pkt_meta;
- ctrl_data_t data;
-};
-
-#endif /* INCLUDED_CTRL_PACKET_HPP */
diff --git a/host/lib/usrp/b100/dboard_iface.cpp b/host/lib/usrp/b100/dboard_iface.cpp
index 39ad5c5ac..25604da72 100644
--- a/host/lib/usrp/b100/dboard_iface.cpp
+++ b/host/lib/usrp/b100/dboard_iface.cpp
@@ -45,7 +45,7 @@ public:
_spi_iface = spi_iface;
_clock = clock;
_codec = codec;
- _gpio = gpio_core_200::make(_wb_iface, B100_REG_SR_ADDR(B100_SR_GPIO), B100_REG_RB_GPIO);
+ _gpio = gpio_core_200::make(_wb_iface, TOREG(SR_GPIO), REG_RB_GPIO);
//init the clock rate shadows
this->set_clock_rate(UNIT_RX, _clock->get_fpga_clock_rate());
diff --git a/host/lib/usrp/b100/io_impl.cpp b/host/lib/usrp/b100/io_impl.cpp
index 05d701313..723756dcc 100644
--- a/host/lib/usrp/b100/io_impl.cpp
+++ b/host/lib/usrp/b100/io_impl.cpp
@@ -15,15 +15,10 @@
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
-#include "recv_packet_demuxer.hpp"
#include "validate_subdev_spec.hpp"
-#include "async_packet_handler.hpp"
#include "../../transport/super_recv_packet_handler.hpp"
#include "../../transport/super_send_packet_handler.hpp"
#include "b100_impl.hpp"
-#include "b100_regs.hpp"
-#include <uhd/utils/thread_priority.hpp>
-#include <uhd/transport/bounded_buffer.hpp>
#include <boost/bind.hpp>
#include <boost/format.hpp>
#include <boost/bind.hpp>
@@ -36,66 +31,6 @@ using namespace uhd;
using namespace uhd::usrp;
using namespace uhd::transport;
-/***********************************************************************
- * IO Implementation Details
- **********************************************************************/
-struct b100_impl::io_impl{
- io_impl(void):
- async_msg_fifo(1000/*messages deep*/)
- { /* NOP */ }
-
- zero_copy_if::sptr data_transport;
- bounded_buffer<async_metadata_t> async_msg_fifo;
- recv_packet_demuxer::sptr demuxer;
- double tick_rate;
-};
-
-/***********************************************************************
- * Initialize internals within this file
- **********************************************************************/
-void b100_impl::io_init(void){
-
- //clear fifo state machines
- _fpga_ctrl->poke32(B100_REG_CLEAR_FIFO, 0);
-
- //allocate streamer weak ptrs containers
- _rx_streamers.resize(_rx_dsps.size());
- _tx_streamers.resize(1/*known to be 1 dsp*/);
-
- //create new io impl
- _io_impl = UHD_PIMPL_MAKE(io_impl, ());
- _io_impl->demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), B100_RX_SID_BASE);
-
- //now its safe to register the async callback
- _fpga_ctrl->set_async_cb(boost::bind(&b100_impl::handle_async_message, this, _1));
-}
-
-void b100_impl::handle_async_message(managed_recv_buffer::sptr rbuf){
- vrt::if_packet_info_t if_packet_info;
- if_packet_info.num_packet_words32 = rbuf->size()/sizeof(boost::uint32_t);
- const boost::uint32_t *vrt_hdr = rbuf->cast<const boost::uint32_t *>();
- try{
- vrt::if_hdr_unpack_le(vrt_hdr, if_packet_info);
- }
- catch(const std::exception &e){
- UHD_MSG(error) << "Error (handle_async_message): " << e.what() << std::endl;
- }
-
- if (if_packet_info.sid == B100_TX_ASYNC_SID and if_packet_info.packet_type != vrt::if_packet_info_t::PACKET_TYPE_DATA){
-
- //fill in the async metadata
- async_metadata_t metadata;
- load_metadata_from_buff(uhd::wtohx<boost::uint32_t>, metadata, if_packet_info, vrt_hdr, _io_impl->tick_rate);
-
- //push the message onto the queue
- _io_impl->async_msg_fifo.push_with_pop_on_full(metadata);
-
- //print some fastpath messages
- standard_async_msg_prints(metadata);
- }
- else UHD_MSG(error) << "Unknown async packet" << std::endl;
-}
-
void b100_impl::update_rates(void){
const fs_path mb_path = "/mboards/0";
_tree->access<double>(mb_path / "tick_rate").update();
@@ -110,7 +45,6 @@ void b100_impl::update_rates(void){
}
void b100_impl::update_tick_rate(const double rate){
- _io_impl->tick_rate = rate;
//update the tick rate on all existing streamers -> thread safe
for (size_t i = 0; i < _rx_streamers.size(); i++){
@@ -180,8 +114,7 @@ void b100_impl::update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){
bool b100_impl::recv_async_msg(
async_metadata_t &async_metadata, double timeout
){
- boost::this_thread::disable_interruption di; //disable because the wait can throw
- return _io_impl->async_msg_fifo.pop_with_timed_wait(async_metadata, timeout);
+ return _fifo_ctrl->pop_async_msg(async_metadata, timeout);
}
/***********************************************************************
@@ -226,7 +159,7 @@ rx_streamer::sptr b100_impl::get_rx_stream(const uhd::stream_args_t &args_){
_rx_dsps[dsp]->set_nsamps_per_packet(spp); //seems to be a good place to set this
_rx_dsps[dsp]->setup(args);
my_streamer->set_xport_chan_get_buff(chan_i, boost::bind(
- &recv_packet_demuxer::get_recv_buff, _io_impl->demuxer, dsp, _1
+ &recv_packet_demuxer::get_recv_buff, _recv_demuxer, dsp, _1
), true /*flush*/);
my_streamer->set_overflow_handler(chan_i, boost::bind(
&rx_dsp_core_200::handle_overflow, _rx_dsps[dsp]
diff --git a/host/lib/usrp/common/CMakeLists.txt b/host/lib/usrp/common/CMakeLists.txt
index 9abd34afa..fa07e3d1d 100644
--- a/host/lib/usrp/common/CMakeLists.txt
+++ b/host/lib/usrp/common/CMakeLists.txt
@@ -1,5 +1,5 @@
#
-# Copyright 2011 Ettus Research LLC
+# Copyright 2011-2012 Ettus Research LLC
#
# This program is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
@@ -32,4 +32,5 @@ 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
+ ${CMAKE_CURRENT_SOURCE_DIR}/fifo_ctrl_excelsior.cpp
)
diff --git a/host/lib/usrp/common/apply_corrections.cpp b/host/lib/usrp/common/apply_corrections.cpp
index b889266f2..3d33e7d11 100644
--- a/host/lib/usrp/common/apply_corrections.cpp
+++ b/host/lib/usrp/common/apply_corrections.cpp
@@ -54,6 +54,12 @@ static bool fe_cal_comp(fe_cal_t a, fe_cal_t b){
static uhd::dict<std::string, std::vector<fe_cal_t> > fe_cal_cache;
+static bool is_same_freq(const double f1, const double f2)
+{
+ const double epsilon = 0.1;
+ return ((f1 - epsilon) < f2 and (f1 + epsilon) > f2);
+}
+
static std::complex<double> get_fe_correction(
const std::string &key, const double lo_freq
){
@@ -64,6 +70,12 @@ static std::complex<double> get_fe_correction(
size_t lo_index = 0;
size_t hi_index = datas.size()-1;
for (size_t i = 0; i < datas.size(); i++){
+ if (is_same_freq(datas[i].lo_freq, lo_freq))
+ {
+ hi_index = i;
+ lo_index = i;
+ break;
+ }
if (datas[i].lo_freq > lo_freq){
hi_index = i;
break;
diff --git a/host/lib/usrp/common/fifo_ctrl_excelsior.cpp b/host/lib/usrp/common/fifo_ctrl_excelsior.cpp
new file mode 100644
index 000000000..5e4a1e243
--- /dev/null
+++ b/host/lib/usrp/common/fifo_ctrl_excelsior.cpp
@@ -0,0 +1,293 @@
+//
+// 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 "fifo_ctrl_excelsior.hpp"
+#include "async_packet_handler.hpp"
+#include <uhd/exception.hpp>
+#include <uhd/utils/msg.hpp>
+#include <uhd/utils/byteswap.hpp>
+#include <uhd/utils/tasks.hpp>
+#include <uhd/utils/safe_call.hpp>
+#include <uhd/utils/thread_priority.hpp>
+#include <uhd/transport/vrt_if_packet.hpp>
+#include <uhd/transport/bounded_buffer.hpp>
+#include <boost/thread/mutex.hpp>
+#include <boost/thread/thread.hpp>
+#include <boost/format.hpp>
+#include <boost/bind.hpp>
+
+using namespace uhd;
+using namespace uhd::usrp;
+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 _config.spi_base + 0
+#define SPI_CTRL _config.spi_base + 4
+#define SPI_DATA _config.spi_base + 8
+#define SPI_DIVIDER 4
+
+struct ctrl_result_t{
+ boost::uint32_t msg[2];
+};
+
+class fifo_ctrl_excelsior_impl : public fifo_ctrl_excelsior{
+public:
+
+ fifo_ctrl_excelsior_impl(zero_copy_if::sptr xport, const fifo_ctrl_excelsior_config &config):
+ _xport(xport),
+ _config(config),
+ _seq_out(0),
+ _seq_ack(0),
+ _timeout(ACK_TIMEOUT),
+ _async_fifo(1000),
+ _ctrl_fifo(MAX_SEQS_OUT+1)
+ {
+ 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
+ _msg_task = task::make(boost::bind(&fifo_ctrl_excelsior_impl::handle_msg, this));
+ this->init_spi();
+ }
+
+ ~fifo_ctrl_excelsior_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
+ )
+ }
+
+ bool pop_async_msg(async_metadata_t &async_metadata, double timeout){
+ boost::this_thread::disable_interruption di; //disable because the wait can throw
+ return _async_fifo.pop_with_timed_wait(async_metadata, timeout);
+ }
+
+ void handle_msg(void){
+ set_thread_priority_safe();
+ while (not boost::this_thread::interruption_requested()){
+ this->handle_msg1();
+ }
+ }
+
+ void handle_msg1(void){
+ managed_recv_buffer::sptr buff = _xport->get_recv_buff();
+ if (not buff) return;
+ 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);
+ try{
+ vrt::if_hdr_unpack_le(pkt, packet_info);
+ }
+ catch(const std::exception &ex){
+ UHD_MSG(error) << "FIFO ctrl bad VITA packet: " << ex.what() << std::endl;
+ }
+ if (packet_info.has_sid and packet_info.sid == _config.ctrl_sid_base){
+ ctrl_result_t res = ctrl_result_t();
+ res.msg[0] = uhd::wtohx(pkt[packet_info.num_header_words32+0]);
+ res.msg[1] = uhd::wtohx(pkt[packet_info.num_header_words32+1]);
+ _ctrl_fifo.push_with_haste(res);
+ }
+ else if (packet_info.has_sid and packet_info.sid >= _config.async_sid_base and packet_info.sid <= _config.async_sid_base + _config.num_async_chan){
+ async_metadata_t metadata;
+ load_metadata_from_buff(uhd::wtohx<boost::uint32_t>, metadata, packet_info, pkt, _tick_rate, packet_info.sid - _config.async_sid_base);
+ _async_fifo.push_with_pop_on_full(metadata);
+ standard_async_msg_prints(metadata);
+ }
+ else{
+ UHD_MSG(error) << "FIFO ctrl got unknown SID: " << packet_info.sid << std::endl;
+ }
+ }
+
+ /*******************************************************************
+ * 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, 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, 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(_config.spi_rb, 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 *pkt = buff->cast<boost::uint32_t *>();
+
+ //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_le(pkt, packet_info);
+
+ //load payload
+ const boost::uint32_t ctrl_word = (addr/4 & 0xff) | cmd | (_seq_out << 16);
+ pkt[packet_info.num_header_words32+0] = uhd::htowx(ctrl_word);
+ pkt[packet_info.num_header_words32+1] = uhd::htowx(data);
+
+ //send the buffer over the interface
+ buff->commit(sizeof(boost::uint32_t)*(packet_info.num_packet_words32));
+ }
+
+ 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)){
+ ctrl_result_t res = ctrl_result_t();
+ if (not _ctrl_fifo.pop_with_timed_wait(res, _timeout)){
+ throw uhd::runtime_error("fifo ctrl timed out looking for acks");
+ }
+ _seq_ack = res.msg[0] >> 16;
+ if (_seq_ack == seq_to_ack) return res.msg[1];
+ }
+
+ return 0;
+ }
+
+ zero_copy_if::sptr _xport;
+ const fifo_ctrl_excelsior_config _config;
+ 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;
+ bounded_buffer<async_metadata_t> _async_fifo;
+ bounded_buffer<ctrl_result_t> _ctrl_fifo;
+ task::sptr _msg_task;
+};
+
+
+fifo_ctrl_excelsior::sptr fifo_ctrl_excelsior::make(zero_copy_if::sptr xport, const fifo_ctrl_excelsior_config &config)
+{
+ return sptr(new fifo_ctrl_excelsior_impl(xport, config));
+}
diff --git a/host/lib/usrp/common/fifo_ctrl_excelsior.hpp b/host/lib/usrp/common/fifo_ctrl_excelsior.hpp
new file mode 100644
index 000000000..c3ef65a2c
--- /dev/null
+++ b/host/lib/usrp/common/fifo_ctrl_excelsior.hpp
@@ -0,0 +1,63 @@
+//
+// 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_B200_CTRL_HPP
+#define INCLUDED_B200_CTRL_HPP
+
+#include <uhd/types/time_spec.hpp>
+#include <uhd/types/metadata.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>
+
+
+struct fifo_ctrl_excelsior_config
+{
+ size_t async_sid_base;
+ size_t num_async_chan;
+ size_t ctrl_sid_base;
+ size_t spi_base;
+ size_t spi_rb;
+};
+
+/*!
+ * Provide access to peek, poke, spi, and async messages.
+ */
+class fifo_ctrl_excelsior : public wb_iface, public uhd::spi_iface{
+public:
+ typedef boost::shared_ptr<fifo_ctrl_excelsior> sptr;
+
+ //! Make a new control object
+ static sptr make(
+ uhd::transport::zero_copy_if::sptr xport,
+ const fifo_ctrl_excelsior_config &config
+ );
+
+ //! 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;
+
+ //! Pop an async message from the queue or timeout
+ virtual bool pop_async_msg(uhd::async_metadata_t &async_metadata, double timeout) = 0;
+};
+
+#endif /* INCLUDED_B200_CTRL_HPP */
diff --git a/host/lib/usrp/common/fx2_ctrl.cpp b/host/lib/usrp/common/fx2_ctrl.cpp
index fab9a59d8..93303542e 100644
--- a/host/lib/usrp/common/fx2_ctrl.cpp
+++ b/host/lib/usrp/common/fx2_ctrl.cpp
@@ -410,6 +410,26 @@ public:
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);
@@ -427,12 +447,7 @@ public:
{
UHD_ASSERT_THROW(bytes.size() < max_i2c_data_bytes);
- unsigned char buff[max_i2c_data_bytes] = {};
- std::copy(bytes.begin(), bytes.end(), buff);
-
- int ret = this->usrp_i2c_write(addr & 0xff,
- buff,
- bytes.size());
+ 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");
@@ -442,19 +457,13 @@ public:
{
UHD_ASSERT_THROW(num_bytes < max_i2c_data_bytes);
- unsigned char buff[max_i2c_data_bytes] = {};
- int ret = this->usrp_i2c_read(addr & 0xff,
- buff,
- num_bytes);
+ 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");
- byte_vector_t out_bytes;
- for (size_t i = 0; i < num_bytes; i++)
- out_bytes.push_back(buff[i]);
-
- return out_bytes;
+ return bytes;
}
diff --git a/host/lib/usrp/cores/CMakeLists.txt b/host/lib/usrp/cores/CMakeLists.txt
index aa5f0bcbb..3192b0774 100644
--- a/host/lib/usrp/cores/CMakeLists.txt
+++ b/host/lib/usrp/cores/CMakeLists.txt
@@ -24,6 +24,7 @@ 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
diff --git a/host/lib/usrp/cores/gpio_core_200.cpp b/host/lib/usrp/cores/gpio_core_200.cpp
index d756097ff..cdab70b8d 100644
--- a/host/lib/usrp/cores/gpio_core_200.cpp
+++ b/host/lib/usrp/cores/gpio_core_200.cpp
@@ -63,6 +63,7 @@ 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;
@@ -90,7 +91,12 @@ private:
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));
- _iface->poke32(addr, (ctrl & atr_val) | ((~ctrl) & gpio_val));
+ 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;
}
};
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
index b73baa81e..ef6b85de9 100644
--- a/host/lib/usrp/cores/rx_dsp_core_200.cpp
+++ b/host/lib/usrp/cores/rx_dsp_core_200.cpp
@@ -19,6 +19,7 @@
#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
@@ -76,8 +77,17 @@ public:
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, 1); //also reset
+ _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
@@ -174,6 +184,15 @@ public:
_iface->poke32(REG_DSP_RX_DECIM, (hb1 << 9) | (hb0 << 8) | (decim & 0xff));
+ if (decim > 1 and hb0 == 0 and hb1 == 0)
+ {
+ UHD_MSG(warning) << boost::format(
+ "The requested decimation is odd; the user should expect CIC rolloff.\n"
+ "Select an even decimation to ensure that a halfband filter is enabled.\n"
+ "decimation = dsp_rate/samp_rate -> %d = (%f MHz)/(%f MHz)\n"
+ ) % decim_rate % (_tick_rate/1e6) % (rate/1e6);
+ }
+
// 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);
diff --git a/host/lib/usrp/cores/time64_core_200.cpp b/host/lib/usrp/cores/time64_core_200.cpp
index e460d1106..11b310362 100644
--- a/host/lib/usrp/cores/time64_core_200.cpp
+++ b/host/lib/usrp/cores/time64_core_200.cpp
@@ -56,6 +56,10 @@ public:
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;
}
@@ -100,7 +104,7 @@ public:
assert_has(_sources, source, "time source");
//setup pps flags
- if (source == "external"){
+ if (source == "external" or source == "gpsdo"){
_iface->poke32(REG_TIME64_FLAGS, FLAG_TIME64_PPS_SMA | FLAG_TIME64_PPS_POSEDGE);
}
else if (source == "_external_"){
diff --git a/host/lib/usrp/cores/time64_core_200.hpp b/host/lib/usrp/cores/time64_core_200.hpp
index 7571573a5..315f2ba67 100644
--- a/host/lib/usrp/cores/time64_core_200.hpp
+++ b/host/lib/usrp/cores/time64_core_200.hpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -42,6 +42,8 @@ public:
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;
diff --git a/host/lib/usrp/cores/tx_dsp_core_200.cpp b/host/lib/usrp/cores/tx_dsp_core_200.cpp
index f905a7551..808f13028 100644
--- a/host/lib/usrp/cores/tx_dsp_core_200.cpp
+++ b/host/lib/usrp/cores/tx_dsp_core_200.cpp
@@ -126,6 +126,15 @@ public:
_iface->poke32(REG_DSP_TX_INTERP, (hb1 << 9) | (hb0 << 8) | (interp & 0xff));
+ if (interp > 1 and hb0 == 0 and hb1 == 0)
+ {
+ UHD_MSG(warning) << boost::format(
+ "The requested interpolation is odd; the user should expect CIC rolloff.\n"
+ "Select an even interpolation to ensure that a halfband filter is enabled.\n"
+ "interpolation = dsp_rate/samp_rate -> %d = (%f MHz)/(%f MHz)\n"
+ ) % interp_rate % (_tick_rate/1e6) % (rate/1e6);
+ }
+
// 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);
diff --git a/host/lib/usrp/dboard/db_basic_and_lf.cpp b/host/lib/usrp/dboard/db_basic_and_lf.cpp
index fc42a73d5..2b30dab52 100644
--- a/host/lib/usrp/dboard/db_basic_and_lf.cpp
+++ b/host/lib/usrp/dboard/db_basic_and_lf.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -108,11 +108,17 @@ basic_rx::basic_rx(ctor_args_t args, double max_freq) : rx_dboard_base(args){
////////////////////////////////////////////////////////////////////
// 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()
+ 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);
@@ -157,11 +163,17 @@ basic_tx::basic_tx(ctor_args_t args, double max_freq) : tx_dboard_base(args){
////////////////////////////////////////////////////////////////////
// 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()
+ 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);
diff --git a/host/lib/usrp/dboard/db_dbsrx.cpp b/host/lib/usrp/dboard/db_dbsrx.cpp
index 95c5c5d4d..b1cee4aa7 100644
--- a/host/lib/usrp/dboard/db_dbsrx.cpp
+++ b/host/lib/usrp/dboard/db_dbsrx.cpp
@@ -202,7 +202,7 @@ dbsrx::dbsrx(ctor_args_t args) : rx_dboard_base(args){
// Register properties
////////////////////////////////////////////////////////////////////
this->get_rx_subtree()->create<std::string>("name")
- .set(get_rx_id().to_pp_string());
+ .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()){
diff --git a/host/lib/usrp/dboard/db_dbsrx2.cpp b/host/lib/usrp/dboard/db_dbsrx2.cpp
index 517b7b183..013f3178a 100644
--- a/host/lib/usrp/dboard/db_dbsrx2.cpp
+++ b/host/lib/usrp/dboard/db_dbsrx2.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -189,7 +189,7 @@ dbsrx2::dbsrx2(ctor_args_t args) : rx_dboard_base(args){
// Register properties
////////////////////////////////////////////////////////////////////
this->get_rx_subtree()->create<std::string>("name")
- .set(get_rx_id().to_pp_string());
+ .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()){
diff --git a/host/lib/usrp/dboard/db_rfx.cpp b/host/lib/usrp/dboard/db_rfx.cpp
index 32aa3fe04..cf3b29ddc 100644
--- a/host/lib/usrp/dboard/db_rfx.cpp
+++ b/host/lib/usrp/dboard/db_rfx.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -174,7 +174,14 @@ rfx_xcvr::rfx_xcvr(
////////////////////////////////////////////////////////////////////
// Register RX properties
////////////////////////////////////////////////////////////////////
- this->get_rx_subtree()->create<std::string>("name").set("RFX RX");
+ 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()){
@@ -203,7 +210,14 @@ rfx_xcvr::rfx_xcvr(
////////////////////////////////////////////////////////////////////
// Register TX properties
////////////////////////////////////////////////////////////////////
- this->get_tx_subtree()->create<std::string>("name").set("RFX TX");
+ 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
@@ -258,7 +272,7 @@ void rfx_xcvr::set_rx_ant(const std::string &ant){
//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_DIS);
+ 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 );
}
@@ -358,7 +372,7 @@ double rfx_xcvr::set_lo_freq(
* 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 exists when it meets all of the constraints.
+ * 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
diff --git a/host/lib/usrp/dboard/db_sbx_common.cpp b/host/lib/usrp/dboard/db_sbx_common.cpp
index d1cd5b373..728cb17e9 100644
--- a/host/lib/usrp/dboard/db_sbx_common.cpp
+++ b/host/lib/usrp/dboard/db_sbx_common.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -16,7 +16,6 @@
//
#include "db_sbx_common.hpp"
-#include "adf4350_regs.hpp"
using namespace uhd;
using namespace uhd::usrp;
@@ -127,7 +126,10 @@ sbx_xcvr::sbx_xcvr(ctor_args_t args) : xcvr_dboard_base(args){
////////////////////////////////////////////////////////////////////
// Register RX properties
////////////////////////////////////////////////////////////////////
- this->get_rx_subtree()->create<std::string>("name").set("SBX RX");
+ 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()){
@@ -156,7 +158,10 @@ sbx_xcvr::sbx_xcvr(ctor_args_t args) : xcvr_dboard_base(args){
////////////////////////////////////////////////////////////////////
// Register TX properties
////////////////////////////////////////////////////////////////////
- this->get_tx_subtree()->create<std::string>("name").set("SBX TX");
+ 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()){
@@ -213,8 +218,8 @@ void sbx_xcvr::update_atr(void){
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 = get_locked(dboard_iface::UNIT_RX).to_bool() ? 0 : RX_LED_LD;
- int tx_ld_led = get_locked(dboard_iface::UNIT_TX).to_bool() ? 0 : TX_LED_LD;
+ 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;
@@ -283,8 +288,14 @@ void sbx_xcvr::set_tx_ant(const std::string &ant){
**********************************************************************/
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_freq = actual;
- if (unit == dboard_iface::UNIT_TX) _tx_lo_freq = actual;
+ 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;
}
@@ -292,6 +303,13 @@ double sbx_xcvr::set_lo_freq(dboard_iface::unit_t unit, double target_freq) {
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");
}
diff --git a/host/lib/usrp/dboard/db_sbx_common.hpp b/host/lib/usrp/dboard/db_sbx_common.hpp
index 501a7f1fc..2a0e83115 100644
--- a/host/lib/usrp/dboard/db_sbx_common.hpp
+++ b/host/lib/usrp/dboard/db_sbx_common.hpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -138,6 +138,7 @@ 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);
diff --git a/host/lib/usrp/dboard/db_sbx_version3.cpp b/host/lib/usrp/dboard/db_sbx_version3.cpp
index 6e20d5882..2765d530c 100644
--- a/host/lib/usrp/dboard/db_sbx_version3.cpp
+++ b/host/lib/usrp/dboard/db_sbx_version3.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -75,7 +75,6 @@ double sbx_xcvr::sbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
if(ref_freq <= 12.5e6) D = adf4350_regs_t::REFERENCE_DOUBLER_ENABLED;
//increase RF divider until acceptable VCO frequency
- //start with target_freq*2 because mixer has divide by 2
double vco_freq = target_freq;
while (vco_freq < 2.2e9) {
vco_freq *= 2;
@@ -83,7 +82,7 @@ double sbx_xcvr::sbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
}
//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;
+ 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,
@@ -91,7 +90,7 @@ double sbx_xcvr::sbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
* (frac) dividers.
*
* Calculate the N and F dividers for each set of values.
- * The loop exists when it meets all of the constraints.
+ * The loop exits when it meets all of the constraints.
* The resulting loop values are loaded into the registers.
*
* from pg.21
@@ -110,7 +109,7 @@ double sbx_xcvr::sbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
if (pfd_freq > 25e6) continue;
//ignore fractional part of tuning
- N = int(std::floor(vco_freq/pfd_freq));
+ N = int(std::floor(target_freq/pfd_freq));
//keep N > minimum int divider requirement
if (N < prescaler_to_min_int_div[prescaler]) continue;
@@ -125,7 +124,7 @@ double sbx_xcvr::sbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
//Fractional-N calculation
MOD = 4095; //max fractional accuracy
- FRAC = int((vco_freq/pfd_freq - N)*MOD);
+ 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
@@ -135,12 +134,12 @@ double sbx_xcvr::sbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
}
//actual frequency calculation
- actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))/RFdiv);
+ 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, LD=%s"
- ) % R % BS % N % FRAC % MOD % T % D % RFdiv % self_base->get_locked(unit).to_pp_string() << 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;
@@ -155,6 +154,9 @@ double sbx_xcvr::sbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
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;
@@ -163,6 +165,11 @@ double sbx_xcvr::sbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
UHD_ASSERT_THROW(rfdivsel_to_enum.has_key(RFdiv));
regs.rf_divider_select = rfdivsel_to_enum[RFdiv];
+ //reset the N and R counter
+ regs.counter_reset = adf4350_regs_t::COUNTER_RESET_ENABLED;
+ self_base->get_iface()->write_spi(unit, spi_config_t::EDGE_RISE, regs.get_reg(2), 32);
+ regs.counter_reset = adf4350_regs_t::COUNTER_RESET_DISABLED;
+
//write the registers
//correct power-up sequence to write registers (5, 4, 3, 2, 1, 0)
int addr;
diff --git a/host/lib/usrp/dboard/db_sbx_version4.cpp b/host/lib/usrp/dboard/db_sbx_version4.cpp
index c8128d5f4..27fd68b05 100644
--- a/host/lib/usrp/dboard/db_sbx_version4.cpp
+++ b/host/lib/usrp/dboard/db_sbx_version4.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -78,7 +78,6 @@ double sbx_xcvr::sbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
if(ref_freq <= 12.5e6) D = adf4351_regs_t::REFERENCE_DOUBLER_ENABLED;
//increase RF divider until acceptable VCO frequency
- //start with target_freq*2 because mixer has divide by 2
double vco_freq = target_freq;
while (vco_freq < 2.2e9) {
vco_freq *= 2;
@@ -86,7 +85,7 @@ double sbx_xcvr::sbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
}
//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;
+ 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,
@@ -94,7 +93,7 @@ double sbx_xcvr::sbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
* (frac) dividers.
*
* Calculate the N and F dividers for each set of values.
- * The loop exists when it meets all of the constraints.
+ * The loop exits when it meets all of the constraints.
* The resulting loop values are loaded into the registers.
*
* from pg.21
@@ -128,7 +127,7 @@ double sbx_xcvr::sbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
//Fractional-N calculation
MOD = 4095; //max fractional accuracy
- FRAC = int((vco_freq/pfd_freq - N)*MOD);
+ 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
@@ -138,12 +137,12 @@ double sbx_xcvr::sbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
}
//actual frequency calculation
- actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))/RFdiv);
+ 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, LD=%s"
- ) % R % BS % N % FRAC % MOD % T % D % RFdiv % self_base->get_locked(unit).to_pp_string() << 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;
@@ -158,6 +157,9 @@ double sbx_xcvr::sbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
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;
@@ -166,6 +168,11 @@ double sbx_xcvr::sbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
UHD_ASSERT_THROW(rfdivsel_to_enum.has_key(RFdiv));
regs.rf_divider_select = rfdivsel_to_enum[RFdiv];
+ //reset the N and R counter
+ regs.counter_reset = adf4351_regs_t::COUNTER_RESET_ENABLED;
+ self_base->get_iface()->write_spi(unit, spi_config_t::EDGE_RISE, regs.get_reg(2), 32);
+ regs.counter_reset = adf4351_regs_t::COUNTER_RESET_DISABLED;
+
//write the registers
//correct power-up sequence to write registers (5, 4, 3, 2, 1, 0)
int addr;
diff --git a/host/lib/usrp/dboard/db_tvrx.cpp b/host/lib/usrp/dboard/db_tvrx.cpp
index fd86d5b83..edee46cd5 100644
--- a/host/lib/usrp/dboard/db_tvrx.cpp
+++ b/host/lib/usrp/dboard/db_tvrx.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -186,7 +186,7 @@ tvrx::tvrx(ctor_args_t args) : rx_dboard_base(args){
// Register properties
////////////////////////////////////////////////////////////////////
this->get_rx_subtree()->create<std::string>("name")
- .set(get_rx_id().to_pp_string());
+ .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")
diff --git a/host/lib/usrp/dboard/db_tvrx2.cpp b/host/lib/usrp/dboard/db_tvrx2.cpp
index 628221527..0bfa5229a 100644
--- a/host/lib/usrp/dboard/db_tvrx2.cpp
+++ b/host/lib/usrp/dboard/db_tvrx2.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010 Ettus Research LLC
+// 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
@@ -955,7 +955,7 @@ tvrx2::tvrx2(ctor_args_t args) : rx_dboard_base(args){
// Register properties
////////////////////////////////////////////////////////////////////
this->get_rx_subtree()->create<std::string>("name")
- .set(get_rx_id().to_pp_string());
+ .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")
diff --git a/host/lib/usrp/dboard/db_wbx_common.cpp b/host/lib/usrp/dboard/db_wbx_common.cpp
index 58ce03d79..503e5aabf 100644
--- a/host/lib/usrp/dboard/db_wbx_common.cpp
+++ b/host/lib/usrp/dboard/db_wbx_common.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -16,7 +16,6 @@
//
#include "db_wbx_common.hpp"
-#include "adf4350_regs.hpp"
#include <uhd/types/dict.hpp>
#include <uhd/types/ranges.hpp>
#include <uhd/types/sensors.hpp>
diff --git a/host/lib/usrp/dboard/db_wbx_simple.cpp b/host/lib/usrp/dboard/db_wbx_simple.cpp
index 3d633a672..4ba30255d 100644
--- a/host/lib/usrp/dboard/db_wbx_simple.cpp
+++ b/host/lib/usrp/dboard/db_wbx_simple.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -81,8 +81,10 @@ wbx_simple::wbx_simple(ctor_args_t args) : wbx_base(args){
////////////////////////////////////////////////////////////////////
// Register RX properties
////////////////////////////////////////////////////////////////////
+
this->get_rx_subtree()->access<std::string>("name").set(
- this->get_rx_subtree()->access<std::string>("name").get() + " + Simple GDB");
+ 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");
@@ -93,7 +95,8 @@ wbx_simple::wbx_simple(ctor_args_t args) : wbx_base(args){
// Register TX properties
////////////////////////////////////////////////////////////////////
this->get_tx_subtree()->access<std::string>("name").set(
- this->get_tx_subtree()->access<std::string>("name").get() + " + Simple GDB");
+ 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));
diff --git a/host/lib/usrp/dboard/db_wbx_version2.cpp b/host/lib/usrp/dboard/db_wbx_version2.cpp
index ad31339e7..5f6118a91 100644
--- a/host/lib/usrp/dboard/db_wbx_version2.cpp
+++ b/host/lib/usrp/dboard/db_wbx_version2.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -78,7 +78,7 @@ wbx_base::wbx_version2::wbx_version2(wbx_base *_self_wbx_base) {
////////////////////////////////////////////////////////////////////
// Register RX properties
////////////////////////////////////////////////////////////////////
- this->get_rx_subtree()->create<std::string>("name").set("WBX RX v2");
+ 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);
@@ -87,7 +87,7 @@ wbx_base::wbx_version2::wbx_version2(wbx_base *_self_wbx_base) {
////////////////////////////////////////////////////////////////////
// Register TX properties
////////////////////////////////////////////////////////////////////
- this->get_tx_subtree()->create<std::string>("name").set("WBX TX v2");
+ 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))
@@ -166,6 +166,9 @@ double wbx_base::wbx_version2::set_lo_freq(dboard_iface::unit_t unit, double tar
"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
@@ -193,12 +196,13 @@ double wbx_base::wbx_version2::set_lo_freq(dboard_iface::unit_t unit, double tar
if(ref_freq <= 12.5e6) D = adf4350_regs_t::REFERENCE_DOUBLER_ENABLED;
//increase RF divider until acceptable VCO frequency
- //start with target_freq*2 because mixer has divide by 2
- double vco_freq = target_freq*2;
+ 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;
@@ -209,7 +213,7 @@ double wbx_base::wbx_version2::set_lo_freq(dboard_iface::unit_t unit, double tar
* (frac) dividers.
*
* Calculate the N and F dividers for each set of values.
- * The loop exists when it meets all of the constraints.
+ * The loop exits when it meets all of the constraints.
* The resulting loop values are loaded into the registers.
*
* from pg.21
@@ -253,14 +257,13 @@ double wbx_base::wbx_version2::set_lo_freq(dboard_iface::unit_t unit, double tar
}
//actual frequency calculation
- actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))/RFdiv/2);
-
+ 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, LD=%s"
- ) % R % BS % N % FRAC % MOD % T % D % RFdiv % self_base->get_locked(unit).to_pp_string() << 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;
@@ -270,6 +273,12 @@ double wbx_base::wbx_version2::set_lo_freq(dboard_iface::unit_t unit, double tar
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;
@@ -307,6 +316,11 @@ double wbx_base::wbx_version2::set_lo_freq(dboard_iface::unit_t unit, double tar
}
+ //reset the N and R counter
+ regs.counter_reset = adf4350_regs_t::COUNTER_RESET_ENABLED;
+ self_base->get_iface()->write_spi(unit, spi_config_t::EDGE_RISE, regs.get_reg(2), 32);
+ regs.counter_reset = adf4350_regs_t::COUNTER_RESET_DISABLED;
+
//write the registers
//correct power-up sequence to write registers (5, 4, 3, 2, 1, 0)
int addr;
diff --git a/host/lib/usrp/dboard/db_wbx_version3.cpp b/host/lib/usrp/dboard/db_wbx_version3.cpp
index 7ef47edd4..3e8fc8095 100644
--- a/host/lib/usrp/dboard/db_wbx_version3.cpp
+++ b/host/lib/usrp/dboard/db_wbx_version3.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -84,7 +84,7 @@ wbx_base::wbx_version3::wbx_version3(wbx_base *_self_wbx_base) {
////////////////////////////////////////////////////////////////////
// Register RX properties
////////////////////////////////////////////////////////////////////
- this->get_rx_subtree()->create<std::string>("name").set("WBX RX v3");
+ 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);
@@ -93,7 +93,7 @@ wbx_base::wbx_version3::wbx_version3(wbx_base *_self_wbx_base) {
////////////////////////////////////////////////////////////////////
// Register TX properties
////////////////////////////////////////////////////////////////////
- this->get_tx_subtree()->create<std::string>("name").set("WBX TX v3");
+ 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))
@@ -198,6 +198,9 @@ double wbx_base::wbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
"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
@@ -225,12 +228,13 @@ double wbx_base::wbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
if(ref_freq <= 12.5e6) D = adf4350_regs_t::REFERENCE_DOUBLER_ENABLED;
//increase RF divider until acceptable VCO frequency
- //start with target_freq*2 because mixer has divide by 2
- double vco_freq = target_freq*2;
+ 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;
@@ -241,7 +245,7 @@ double wbx_base::wbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
* (frac) dividers.
*
* Calculate the N and F dividers for each set of values.
- * The loop exists when it meets all of the constraints.
+ * The loop exits when it meets all of the constraints.
* The resulting loop values are loaded into the registers.
*
* from pg.21
@@ -285,14 +289,13 @@ double wbx_base::wbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
}
//actual frequency calculation
- actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))/RFdiv/2);
-
+ 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, LD=%s"
- ) % R % BS % N % FRAC % MOD % T % D % RFdiv % self_base->get_locked(unit).to_pp_string() << 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;
@@ -302,6 +305,12 @@ double wbx_base::wbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
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;
@@ -339,6 +348,11 @@ double wbx_base::wbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar
}
+ //reset the N and R counter
+ regs.counter_reset = adf4350_regs_t::COUNTER_RESET_ENABLED;
+ self_base->get_iface()->write_spi(unit, spi_config_t::EDGE_RISE, regs.get_reg(2), 32);
+ regs.counter_reset = adf4350_regs_t::COUNTER_RESET_DISABLED;
+
//write the registers
//correct power-up sequence to write registers (5, 4, 3, 2, 1, 0)
int addr;
diff --git a/host/lib/usrp/dboard/db_wbx_version4.cpp b/host/lib/usrp/dboard/db_wbx_version4.cpp
index 2fc3416ee..17b910de4 100644
--- a/host/lib/usrp/dboard/db_wbx_version4.cpp
+++ b/host/lib/usrp/dboard/db_wbx_version4.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -85,7 +85,7 @@ wbx_base::wbx_version4::wbx_version4(wbx_base *_self_wbx_base) {
////////////////////////////////////////////////////////////////////
// Register RX properties
////////////////////////////////////////////////////////////////////
- this->get_rx_subtree()->create<std::string>("name").set("WBX RX v4");
+ 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);
@@ -94,7 +94,7 @@ wbx_base::wbx_version4::wbx_version4(wbx_base *_self_wbx_base) {
////////////////////////////////////////////////////////////////////
// Register TX properties
////////////////////////////////////////////////////////////////////
- this->get_tx_subtree()->create<std::string>("name").set("WBX TX v4");
+ 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))
@@ -200,6 +200,9 @@ double wbx_base::wbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
"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
@@ -229,12 +232,13 @@ double wbx_base::wbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
if(ref_freq <= 12.5e6) D = adf4351_regs_t::REFERENCE_DOUBLER_ENABLED;
//increase RF divider until acceptable VCO frequency
- //start with target_freq*2 because mixer has divide by 2
- double vco_freq = target_freq*2;
+ 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;
@@ -289,14 +293,13 @@ double wbx_base::wbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
}
//actual frequency calculation
- actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))/RFdiv/2);
-
+ 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, LD=%s"
- ) % R % BS % N % FRAC % MOD % T % D % RFdiv % self_base->get_locked(unit).to_pp_string() << 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;
@@ -306,6 +309,12 @@ double wbx_base::wbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
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;
@@ -343,6 +352,11 @@ double wbx_base::wbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar
}
+ //reset the N and R counter
+ regs.counter_reset = adf4351_regs_t::COUNTER_RESET_ENABLED;
+ self_base->get_iface()->write_spi(unit, spi_config_t::EDGE_RISE, regs.get_reg(2), 32);
+ regs.counter_reset = adf4351_regs_t::COUNTER_RESET_DISABLED;
+
//write the registers
//correct power-up sequence to write registers (5, 4, 3, 2, 1, 0)
int addr;
diff --git a/host/lib/usrp/dboard/db_xcvr2450.cpp b/host/lib/usrp/dboard/db_xcvr2450.cpp
index 439e1b35e..348195a6e 100644
--- a/host/lib/usrp/dboard/db_xcvr2450.cpp
+++ b/host/lib/usrp/dboard/db_xcvr2450.cpp
@@ -228,7 +228,7 @@ xcvr2450::xcvr2450(ctor_args_t args) : xcvr_dboard_base(args){
// Register RX properties
////////////////////////////////////////////////////////////////////
this->get_rx_subtree()->create<std::string>("name")
- .set(get_rx_id().to_pp_string());
+ .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")
@@ -266,7 +266,7 @@ xcvr2450::xcvr2450(ctor_args_t args) : xcvr_dboard_base(args){
// Register TX properties
////////////////////////////////////////////////////////////////////
this->get_tx_subtree()->create<std::string>("name")
- .set(get_tx_id().to_pp_string());
+ .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()){
diff --git a/host/lib/usrp/e100/dboard_iface.cpp b/host/lib/usrp/e100/dboard_iface.cpp
index 6afc7bc48..532b2dc9e 100644
--- a/host/lib/usrp/e100/dboard_iface.cpp
+++ b/host/lib/usrp/e100/dboard_iface.cpp
@@ -45,7 +45,7 @@ public:
_spi_iface = spi_iface;
_clock = clock;
_codec = codec;
- _gpio = gpio_core_200::make(_wb_iface, E100_REG_SR_ADDR(UE_SR_GPIO), E100_REG_RB_GPIO);
+ _gpio = gpio_core_200::make(_wb_iface, TOREG(SR_GPIO), REG_RB_GPIO);
//init the clock rate shadows
this->set_clock_rate(UNIT_RX, _clock->get_fpga_clock_rate());
diff --git a/host/lib/usrp/e100/e100_ctrl.cpp b/host/lib/usrp/e100/e100_ctrl.cpp
index eb529c9c1..5a9b93633 100644
--- a/host/lib/usrp/e100/e100_ctrl.cpp
+++ b/host/lib/usrp/e100/e100_ctrl.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2011-2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -23,13 +23,16 @@
#include <sys/ioctl.h> //ioctl
#include <fcntl.h> //open, close
#include <linux/usrp_e.h> //ioctl structures and constants
+#include <poll.h> //poll
#include <boost/thread/thread.hpp> //sleep
#include <boost/thread/mutex.hpp>
+#include <boost/thread/condition_variable.hpp>
#include <boost/foreach.hpp>
#include <boost/format.hpp>
#include <fstream>
using namespace uhd;
+using namespace uhd::transport;
/***********************************************************************
* Sysfs GPIO wrapper class
@@ -71,6 +74,11 @@ private:
};
/***********************************************************************
+ * Protection for dual GPIO access - sometimes MISO, sometimes have resp
+ **********************************************************************/
+static boost::mutex gpio_irq_resp_mutex;
+
+/***********************************************************************
* Aux spi implementation
**********************************************************************/
class aux_spi_iface_impl : public spi_iface{
@@ -87,6 +95,8 @@ public:
size_t num_bits,
bool readback
){
+ boost::mutex::scoped_lock lock(gpio_irq_resp_mutex);
+
boost::uint32_t rb_bits = 0;
this->spi_sen_gpio(0);
@@ -244,6 +254,57 @@ uhd::uart_iface::sptr e100_ctrl::make_gps_uart_iface(const std::string &node){
}
/***********************************************************************
+ * Simple managed buffers
+ **********************************************************************/
+struct e100_simpl_mrb : managed_recv_buffer
+{
+ usrp_e_ctl32 data;
+ e100_ctrl *ctrl;
+
+ void release(void)
+ {
+ //NOP
+ }
+
+ sptr get_new(void)
+ {
+ const size_t max_words32 = 8; //.LAST_ADDR(10'h00f)) resp_fifo_to_gpmc
+
+ //load the data struct
+ data.offset = 0;
+ data.count = max_words32;
+
+ //call the ioctl
+ ctrl->ioctl(USRP_E_READ_CTL32, &data);
+
+ if (data.buf[0] == 0 or ~data.buf[0] == 0) return sptr(); //bad VRT hdr, treat like timeout
+
+ return make(this, data.buf, sizeof(data.buf));
+ }
+};
+
+struct e100_simpl_msb : managed_send_buffer
+{
+ usrp_e_ctl32 data;
+ e100_ctrl *ctrl;
+
+ void release(void)
+ {
+ //load the data struct
+ data.offset = 0;
+ data.count = size()/4+1/*1 for header offset*/;
+
+ //call the ioctl
+ ctrl->ioctl(USRP_E_WRITE_CTL32, &data);
+ }
+
+ sptr get_new(void)
+ {
+ return make(this, data.buf+1, sizeof(data.buf)-4);
+ }
+};
+
+/***********************************************************************
* USRP-E100 control implementation
**********************************************************************/
class e100_ctrl_impl : public e100_ctrl{
@@ -273,11 +334,24 @@ public:
) % USRP_E_COMPAT_NUMBER % module_compat_num));
}
- //perform a global reset after opening
- this->poke32(E100_REG_GLOBAL_RESET, 0);
+ //hit the magic arst condition
+ //async_reset <= ~EM_NCS6 && ~EM_NWE && (EM_A[9:2] == 8'hff) && EM_D[0];
+ usrp_e_ctl16 datax;
+ datax.offset = 0x3fc;
+ datax.count = 2;
+ datax.buf[0] = 1;
+ datax.buf[1] = 0;
+ this->ioctl(USRP_E_WRITE_CTL16, &datax);
+
+ std::ofstream edge_file("/sys/class/gpio/gpio147/edge");
+ edge_file << "rising" << std::endl << std::flush;
+ edge_file.close();
+ _irq_fd = ::open("/sys/class/gpio/gpio147/value", O_RDONLY);
+ if (_irq_fd < 0) UHD_MSG(error) << "Unable to open GPIO for IRQ\n";
}
~e100_ctrl_impl(void){
+ ::close(_irq_fd);
::close(_node_fd);
}
@@ -293,58 +367,76 @@ public:
));
}
}
+
/*******************************************************************
- * Peek and Poke
+ * The managed buffer interface
******************************************************************/
- void poke32(wb_addr_type addr, boost::uint32_t value){
- //load the data struct
- usrp_e_ctl32 data;
- data.offset = addr;
- data.count = 1;
- data.buf[0] = value;
-
- //call the ioctl
- this->ioctl(USRP_E_WRITE_CTL32, &data);
+ UHD_INLINE bool resp_read(void)
+ {
+ //thread stuff ensures that this GPIO isnt shared
+ boost::mutex::scoped_lock lock(gpio_irq_resp_mutex);
+
+ //perform a read of the GPIO IRQ state
+ char ch;
+ ::read(_irq_fd, &ch, sizeof(ch));
+ ::lseek(_irq_fd, SEEK_SET, 0);
+ return ch == '1';
}
- 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;
+ UHD_INLINE bool resp_wait(const double timeout)
+ {
+ //perform a check, if it fails, poll
+ if (this->resp_read()) return true;
- //call the ioctl
- this->ioctl(USRP_E_WRITE_CTL16, &data);
+ //poll IRQ GPIO for some action
+ pollfd pfd;
+ pfd.fd = _irq_fd;
+ pfd.events = POLLPRI | POLLERR;
+ ::poll(&pfd, 1, long(timeout*1000)/*ms*/);
+
+ //perform a GPIO read again for result
+ return this->resp_read();
}
- boost::uint32_t peek32(wb_addr_type addr){
- //load the data struct
- usrp_e_ctl32 data;
- data.offset = addr;
- data.count = 1;
+ managed_recv_buffer::sptr get_recv_buff(double timeout)
+ {
+ if (not this->resp_wait(timeout))
+ {
+ return managed_recv_buffer::sptr();
+ }
- //call the ioctl
- this->ioctl(USRP_E_READ_CTL32, &data);
+ _mrb.ctrl = this;
+ return _mrb.get_new();
+ }
- return data.buf[0];
+ managed_send_buffer::sptr get_send_buff(double)
+ {
+ _msb.ctrl = this;
+ return _msb.get_new();
}
- boost::uint16_t peek16(wb_addr_type addr){
- //load the data struct
- usrp_e_ctl16 data;
- data.offset = addr;
- data.count = 1;
+ size_t get_num_recv_frames(void) const{
+ return 1;
+ }
- //call the ioctl
- this->ioctl(USRP_E_READ_CTL16, &data);
+ size_t get_recv_frame_size(void) const{
+ return sizeof(_mrb.data.buf);
+ }
+
+ size_t get_num_send_frames(void) const{
+ return 1;
+ }
- return data.buf[0];
+ size_t get_send_frame_size(void) const{
+ return sizeof(_msb.data.buf);
}
private:
int _node_fd;
+ int _irq_fd;
boost::mutex _ioctl_mutex;
+ e100_simpl_mrb _mrb;
+ e100_simpl_msb _msb;
};
/***********************************************************************
diff --git a/host/lib/usrp/e100/e100_ctrl.hpp b/host/lib/usrp/e100/e100_ctrl.hpp
index fd66791d4..72dce134e 100644
--- a/host/lib/usrp/e100/e100_ctrl.hpp
+++ b/host/lib/usrp/e100/e100_ctrl.hpp
@@ -1,5 +1,5 @@
//
-// Copyright 2011 Ettus Research LLC
+// Copyright 2012 Ettus Research LLC
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
@@ -18,12 +18,11 @@
#ifndef INCLUDED_B100_CTRL_HPP
#define INCLUDED_B100_CTRL_HPP
-#include "wb_iface.hpp"
+#include <uhd/transport/zero_copy.hpp>
#include <uhd/types/serial.hpp>
#include <boost/shared_ptr.hpp>
-#include <boost/utility.hpp>
-class e100_ctrl : boost::noncopyable, public wb_iface{
+class e100_ctrl : public uhd::transport::zero_copy_if{
public:
typedef boost::shared_ptr<e100_ctrl> sptr;
@@ -33,7 +32,7 @@ public:
//! Make an i2c iface for the i2c device node
static uhd::i2c_iface::sptr make_dev_i2c_iface(const std::string &node);
- //! Make an i2c iface for the i2c device node
+ //! Make a spi iface for the spi gpio
static uhd::spi_iface::sptr make_aux_spi_iface(void);
//! Make a uart iface for the uart device node
diff --git a/host/lib/usrp/e100/e100_impl.cpp b/host/lib/usrp/e100/e100_impl.cpp
index d610c0b12..a0fa6c47e 100644
--- a/host/lib/usrp/e100/e100_impl.cpp
+++ b/host/lib/usrp/e100/e100_impl.cpp
@@ -28,6 +28,7 @@
#include <boost/functional/hash.hpp>
#include <boost/assign/list_of.hpp>
#include <fstream>
+#include <ctime>
using namespace uhd;
using namespace uhd::usrp;
@@ -64,7 +65,7 @@ static device_addrs_t e100_find(const device_addr_t &hint){
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, mboard_eeprom_t::MAP_E100);
+ const mboard_eeprom_t mb_eeprom(*i2c_iface, E100_EEPROM_MAP_KEY);
new_addr["name"] = mb_eeprom["name"];
new_addr["serial"] = mb_eeprom["serial"];
}
@@ -86,15 +87,6 @@ static device_addrs_t e100_find(const device_addr_t &hint){
/***********************************************************************
* Make
**********************************************************************/
-static size_t hash_fpga_file(const std::string &file_path){
- size_t hash = 0;
- std::ifstream file(file_path.c_str());
- if (not file.good()) throw uhd::io_error("cannot open fpga file for read: " + file_path);
- while (file.good()) boost::hash_combine(hash, file.get());
- file.close();
- return hash;
-}
-
static device::sptr e100_make(const device_addr_t &device_addr){
return device::sptr(new e100_impl(device_addr));
}
@@ -114,13 +106,9 @@ static const uhd::dict<std::string, std::string> model_to_fpga_file_name = boost
e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
_tree = property_tree::make();
- //setup the main interface into fpga
- const std::string node = device_addr["node"];
- _fpga_ctrl = e100_ctrl::make(node);
-
//read the eeprom so we can determine the hardware
_dev_i2c_iface = e100_ctrl::make_dev_i2c_iface(E100_I2C_DEV_NODE);
- const mboard_eeprom_t mb_eeprom(*_dev_i2c_iface, mboard_eeprom_t::MAP_E100);
+ 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", ""));
@@ -133,20 +121,19 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
//extract the fpga path and compute hash
const std::string default_fpga_file_name = model_to_fpga_file_name[model];
- const std::string e100_fpga_image = find_image_path(device_addr.get("fpga", default_fpga_file_name));
- const boost::uint32_t file_hash = boost::uint32_t(hash_fpga_file(e100_fpga_image));
-
- //When the hash does not match:
- // - close the device node
- // - load the fpga bin file
- // - re-open the device node
- if (_fpga_ctrl->peek32(E100_REG_RB_MISC_TEST32) != file_hash){
- _fpga_ctrl.reset();
- e100_load_fpga(e100_fpga_image);
- _fpga_ctrl = e100_ctrl::make(node);
+ std::string e100_fpga_image;
+ try{
+ e100_fpga_image = find_image_path(device_addr.get("fpga", default_fpga_file_name));
}
+ catch(...){
+ UHD_MSG(error) << boost::format("Could not find FPGA image. %s\n") % print_images_error();
+ throw;
+ }
+ e100_load_fpga(e100_fpga_image);
- //setup clock control here to ensure that the FPGA has a good clock before we continue
+ ////////////////////////////////////////////////////////////////////
+ // Setup the FPGA clock over AUX SPI
+ ////////////////////////////////////////////////////////////////////
bool dboard_clocks_diff = true;
if (mb_eeprom.get("revision", "0") == "3") dboard_clocks_diff = false;
else if (mb_eeprom.get("revision", "0") == "4") dboard_clocks_diff = true;
@@ -158,12 +145,32 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
_aux_spi_iface = e100_ctrl::make_aux_spi_iface();
_clock_ctrl = e100_clock_ctrl::make(_aux_spi_iface, master_clock_rate, dboard_clocks_diff);
+ ////////////////////////////////////////////////////////////////////
+ // setup the main interface into fpga
+ // - do this after aux spi, because we share gpio147
+ ////////////////////////////////////////////////////////////////////
+ const std::string node = device_addr["node"];
+ _fpga_ctrl = e100_ctrl::make(node);
+
+ ////////////////////////////////////////////////////////////////////
+ // Initialize FPGA control communication
+ ////////////////////////////////////////////////////////////////////
+ fifo_ctrl_excelsior_config fifo_ctrl_config;
+ fifo_ctrl_config.async_sid_base = E100_TX_ASYNC_SID;
+ fifo_ctrl_config.num_async_chan = 1;
+ fifo_ctrl_config.ctrl_sid_base = E100_CTRL_MSG_SID;
+ fifo_ctrl_config.spi_base = TOREG(SR_SPI);
+ fifo_ctrl_config.spi_rb = REG_RB_SPI;
+ _fifo_ctrl = fifo_ctrl_excelsior::make(_fpga_ctrl, fifo_ctrl_config);
+
//Perform wishbone readback tests, these tests also write the hash
bool test_fail = false;
- UHD_MSG(status) << "Performing wishbone readback test... " << std::flush;
+ UHD_MSG(status) << "Performing control readback test... " << std::flush;
+ size_t hash = time(NULL);
for (size_t i = 0; i < 100; i++){
- _fpga_ctrl->poke32(E100_REG_SR_MISC_TEST32, file_hash);
- test_fail = _fpga_ctrl->peek32(E100_REG_RB_MISC_TEST32) != file_hash;
+ boost::hash_combine(hash, i);
+ _fifo_ctrl->poke32(TOREG(SR_MISC+0), boost::uint32_t(hash));
+ test_fail = _fifo_ctrl->peek32(REG_RB_CONFIG0) != boost::uint32_t(hash);
if (test_fail) break; //exit loop on any failure
}
UHD_MSG(status) << ((test_fail)? " fail" : "pass") << std::endl;
@@ -180,8 +187,7 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
////////////////////////////////////////////////////////////////////
// Create controller objects
////////////////////////////////////////////////////////////////////
- _fpga_i2c_ctrl = i2c_core_100::make(_fpga_ctrl, E100_REG_SLAVE(3));
- _fpga_spi_ctrl = spi_core_100::make(_fpga_ctrl, E100_REG_SLAVE(2));
+ _fpga_i2c_ctrl = i2c_core_200::make(_fifo_ctrl, TOREG(SR_I2C), REG_RB_I2C);
_data_transport = e100_make_mmap_zero_copy(_fpga_ctrl);
////////////////////////////////////////////////////////////////////
@@ -189,7 +195,8 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
////////////////////////////////////////////////////////////////////
_tree->create<std::string>("/name").set("E-Series Device");
const fs_path mb_path = "/mboards/0";
- _tree->create<std::string>(mb_path / "name").set(str(boost::format("%s (euewanee)") % model));
+ _tree->create<std::string>(mb_path / "name").set(model);
+ _tree->create<std::string>(mb_path / "codename").set("Euwanee");
////////////////////////////////////////////////////////////////////
// setup the mboard eeprom
@@ -204,12 +211,17 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
//^^^ clock created up top, just reg props here... ^^^
_tree->create<double>(mb_path / "tick_rate")
.publish(boost::bind(&e100_clock_ctrl::get_fpga_clock_rate, _clock_ctrl))
+ .subscribe(boost::bind(&fifo_ctrl_excelsior::set_tick_rate, _fifo_ctrl, _1))
.subscribe(boost::bind(&e100_impl::update_tick_rate, this, _1));
+ //subscribe the command time while we are at it
+ _tree->create<time_spec_t>(mb_path / "time/cmd")
+ .subscribe(boost::bind(&fifo_ctrl_excelsior::set_time, _fifo_ctrl, _1));
+
////////////////////////////////////////////////////////////////////
// create codec control objects
////////////////////////////////////////////////////////////////////
- _codec_ctrl = e100_codec_ctrl::make(_fpga_spi_ctrl);
+ _codec_ctrl = e100_codec_ctrl::make(_fifo_ctrl/*spi*/);
const fs_path rx_codec_path = mb_path / "rx_codecs/A";
const fs_path tx_codec_path = mb_path / "tx_codecs/A";
_tree->create<std::string>(rx_codec_path / "name").set("ad9522");
@@ -231,24 +243,37 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
////////////////////////////////////////////////////////////////////
// Create the GPSDO control
////////////////////////////////////////////////////////////////////
- try{
- _gps = gps_ctrl::make(e100_ctrl::make_gps_uart_iface(E100_UART_DEV_NODE));
- }
- catch(std::exception &e){
- UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl;
- }
- if (_gps.get() != NULL and _gps->gps_detected()){
- BOOST_FOREACH(const std::string &name, _gps->get_sensors()){
- _tree->create<sensor_value_t>(mb_path / "sensors" / name)
- .publish(boost::bind(&gps_ctrl::get_sensor, _gps, name));
+ static const fs::path GPSDO_VOLATILE_PATH("/media/ram/e100_internal_gpsdo.cache");
+ if (not fs::exists(GPSDO_VOLATILE_PATH))
+ {
+ UHD_MSG(status) << "Detecting internal GPSDO.... " << std::flush;
+ try{
+ _gps = gps_ctrl::make(e100_ctrl::make_gps_uart_iface(E100_UART_DEV_NODE));
+ }
+ catch(std::exception &e){
+ UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl;
+ }
+ if (_gps and _gps->gps_detected())
+ {
+ UHD_MSG(status) << "found" << std::endl;
+ BOOST_FOREACH(const std::string &name, _gps->get_sensors())
+ {
+ _tree->create<sensor_value_t>(mb_path / "sensors" / name)
+ .publish(boost::bind(&gps_ctrl::get_sensor, _gps, name));
+ }
+ }
+ else
+ {
+ UHD_MSG(status) << "not found" << std::endl;
+ std::ofstream(GPSDO_VOLATILE_PATH.string().c_str(), std::ofstream::binary) << "42" << std::endl;
}
}
////////////////////////////////////////////////////////////////////
// create frontend control objects
////////////////////////////////////////////////////////////////////
- _rx_fe = rx_frontend_core_200::make(_fpga_ctrl, E100_REG_SR_ADDR(UE_SR_RX_FRONT));
- _tx_fe = tx_frontend_core_200::make(_fpga_ctrl, E100_REG_SR_ADDR(UE_SR_TX_FRONT));
+ _rx_fe = rx_frontend_core_200::make(_fifo_ctrl, TOREG(SR_RX_FE));
+ _tx_fe = tx_frontend_core_200::make(_fifo_ctrl, TOREG(SR_TX_FE));
_tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec")
.subscribe(boost::bind(&e100_impl::update_rx_subdev_spec, this, _1));
@@ -277,13 +302,17 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
////////////////////////////////////////////////////////////////////
// create rx dsp control objects
////////////////////////////////////////////////////////////////////
- _rx_dsps.push_back(rx_dsp_core_200::make(
- _fpga_ctrl, E100_REG_SR_ADDR(UE_SR_RX_DSP0), E100_REG_SR_ADDR(UE_SR_RX_CTRL0), E100_RX_SID_BASE + 0
- ));
- _rx_dsps.push_back(rx_dsp_core_200::make(
- _fpga_ctrl, E100_REG_SR_ADDR(UE_SR_RX_DSP1), E100_REG_SR_ADDR(UE_SR_RX_CTRL1), E100_RX_SID_BASE + 1
- ));
- for (size_t dspno = 0; dspno < _rx_dsps.size(); dspno++){
+ const size_t num_rx_dsps = _fifo_ctrl->peek32(REG_RB_NUM_RX_DSP);
+ for (size_t dspno = 0; dspno < num_rx_dsps; dspno++)
+ {
+ const size_t sr_off = dspno*32;
+ _rx_dsps.push_back(rx_dsp_core_200::make(
+ _fifo_ctrl,
+ TOREG(SR_RX_DSP0+sr_off),
+ TOREG(SR_RX_CTRL0+sr_off),
+ E100_RX_SID_BASE + dspno
+ ));
+
_rx_dsps[dspno]->set_link_rate(E100_RX_LINK_RATE_BPS);
_tree->access<double>(mb_path / "tick_rate")
.subscribe(boost::bind(&rx_dsp_core_200::set_tick_rate, _rx_dsps[dspno], _1));
@@ -306,7 +335,7 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
// create tx dsp control objects
////////////////////////////////////////////////////////////////////
_tx_dsp = tx_dsp_core_200::make(
- _fpga_ctrl, E100_REG_SR_ADDR(UE_SR_TX_DSP), E100_REG_SR_ADDR(UE_SR_TX_CTRL), E100_TX_ASYNC_SID
+ _fifo_ctrl, TOREG(SR_TX_DSP), TOREG(SR_TX_CTRL), E100_TX_ASYNC_SID
);
_tx_dsp->set_link_rate(E100_TX_LINK_RATE_BPS);
_tree->access<double>(mb_path / "tick_rate")
@@ -326,12 +355,12 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
// create time control objects
////////////////////////////////////////////////////////////////////
time64_core_200::readback_bases_type time64_rb_bases;
- time64_rb_bases.rb_hi_now = E100_REG_RB_TIME_NOW_HI;
- time64_rb_bases.rb_lo_now = E100_REG_RB_TIME_NOW_LO;
- time64_rb_bases.rb_hi_pps = E100_REG_RB_TIME_PPS_HI;
- time64_rb_bases.rb_lo_pps = E100_REG_RB_TIME_PPS_LO;
+ time64_rb_bases.rb_hi_now = REG_RB_TIME_NOW_HI;
+ time64_rb_bases.rb_lo_now = REG_RB_TIME_NOW_LO;
+ time64_rb_bases.rb_hi_pps = REG_RB_TIME_PPS_HI;
+ time64_rb_bases.rb_lo_pps = REG_RB_TIME_PPS_LO;
_time64 = time64_core_200::make(
- _fpga_ctrl, E100_REG_SR_ADDR(UE_SR_TIME64), time64_rb_bases
+ _fifo_ctrl, TOREG(SR_TIME64), time64_rb_bases
);
_tree->access<double>(mb_path / "tick_rate")
.subscribe(boost::bind(&time64_core_200::set_tick_rate, _time64, _1));
@@ -349,13 +378,14 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
//setup reference source props
_tree->create<std::string>(mb_path / "clock_source/value")
.subscribe(boost::bind(&e100_impl::update_clock_source, this, _1));
- static const std::vector<std::string> clock_sources = boost::assign::list_of("internal")("external")("auto");
+ 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));
+ _user = user_settings_core_200::make(_fifo_ctrl, TOREG(SR_USER_REGS));
_tree->create<user_settings_core_200::user_reg_t>(mb_path / "user/regs")
.subscribe(boost::bind(&user_settings_core_200::set_reg, _user, _1));
@@ -369,6 +399,9 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
tx_db_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_TX_DB);
gdb_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_TX_DB ^ 5);
+ //disable rx dc offset if LFRX
+ if (rx_db_eeprom.id == 0x000f) _tree->access<bool>(rx_fe_path / "dc_offset" / "enable").set(false);
+
//create the properties and register subscribers
_tree->create<dboard_eeprom_t>(mb_path / "dboards/A/rx_eeprom")
.set(rx_db_eeprom)
@@ -381,7 +414,7 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
.subscribe(boost::bind(&e100_impl::set_db_eeprom, this, "gdb", _1));
//create a new dboard interface and manager
- _dboard_iface = make_e100_dboard_iface(_fpga_ctrl, _fpga_i2c_ctrl, _fpga_spi_ctrl, _clock_ctrl, _codec_ctrl);
+ _dboard_iface = make_e100_dboard_iface(_fifo_ctrl, _fpga_i2c_ctrl, _fifo_ctrl/*spi*/, _clock_ctrl, _codec_ctrl);
_tree->create<dboard_iface::sptr>(mb_path / "dboards/A/iface").set(_dboard_iface);
_dboard_manager = dboard_manager::make(
rx_db_eeprom.id, tx_db_eeprom.id, gdb_eeprom.id,
@@ -401,7 +434,11 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
}
//initialize io handling
- this->io_init();
+ _recv_demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), E100_RX_SID_BASE);
+
+ //allocate streamer weak ptrs containers
+ _rx_streamers.resize(_rx_dsps.size());
+ _tx_streamers.resize(1/*known to be 1 dsp*/);
////////////////////////////////////////////////////////////////////
// do some post-init tasks
@@ -425,10 +462,11 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){
_tree->access<std::string>(mb_path / "time_source/value").set("none");
//GPS installed: use external ref, time, and init time spec
- if (_gps.get() != NULL and _gps->gps_detected()){
+ 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("external");
- _tree->access<std::string>(mb_path / "clock_source/value").set("external");
+ _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)));
}
@@ -448,7 +486,7 @@ double e100_impl::update_rx_codec_gain(const double gain){
}
void e100_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){
- mb_eeprom.commit(*_dev_i2c_iface, mboard_eeprom_t::MAP_E100);
+ 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){
@@ -458,9 +496,23 @@ void e100_impl::set_db_eeprom(const std::string &type, const uhd::usrp::dboard_e
}
void e100_impl::update_clock_source(const std::string &source){
+
+ if (source == "pps_sync"){
+ _clock_ctrl->use_external_ref();
+ _fifo_ctrl->poke32(TOREG(SR_MISC+2), 1);
+ return;
+ }
+ if (source == "_pps_sync_"){
+ _clock_ctrl->use_external_ref();
+ _fifo_ctrl->poke32(TOREG(SR_MISC+2), 3);
+ return;
+ }
+ _fifo_ctrl->poke32(TOREG(SR_MISC+2), 0);
+
if (source == "auto") _clock_ctrl->use_auto_ref();
else if (source == "internal") _clock_ctrl->use_internal_ref();
else if (source == "external") _clock_ctrl->use_external_ref();
+ else if (source == "gpsdo") _clock_ctrl->use_external_ref();
else throw uhd::runtime_error("unhandled clock configuration reference source: " + source);
}
@@ -470,7 +522,7 @@ sensor_value_t e100_impl::get_ref_locked(void){
}
void e100_impl::check_fpga_compat(void){
- const boost::uint32_t fpga_compat_num = _fpga_ctrl->peek32(E100_REG_RB_COMPAT);
+ const boost::uint32_t fpga_compat_num = _fifo_ctrl->peek32(REG_RB_COMPAT);
boost::uint16_t fpga_major = fpga_compat_num >> 16, fpga_minor = fpga_compat_num & 0xffff;
if (fpga_major == 0){ //old version scheme
fpga_major = fpga_minor;
diff --git a/host/lib/usrp/e100/e100_impl.hpp b/host/lib/usrp/e100/e100_impl.hpp
index 1d36cb2ac..6f64d4b80 100644
--- a/host/lib/usrp/e100/e100_impl.hpp
+++ b/host/lib/usrp/e100/e100_impl.hpp
@@ -18,17 +18,17 @@
#include "e100_ctrl.hpp"
#include "clock_ctrl.hpp"
#include "codec_ctrl.hpp"
-#include "spi_core_100.hpp"
-#include "i2c_core_100.hpp"
+#include "i2c_core_200.hpp"
#include "rx_frontend_core_200.hpp"
#include "tx_frontend_core_200.hpp"
#include "rx_dsp_core_200.hpp"
#include "tx_dsp_core_200.hpp"
#include "time64_core_200.hpp"
+#include "fifo_ctrl_excelsior.hpp"
#include "user_settings_core_200.hpp"
+#include "recv_packet_demuxer.hpp"
#include <uhd/device.hpp>
#include <uhd/property_tree.hpp>
-#include <uhd/utils/pimpl.hpp>
#include <uhd/usrp/subdev_spec.hpp>
#include <uhd/usrp/dboard_eeprom.hpp>
#include <uhd/usrp/mboard_eeprom.hpp>
@@ -49,10 +49,12 @@ 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 = 0x09;
-static const boost::uint32_t E100_RX_SID_BASE = 2;
-static const boost::uint32_t E100_TX_ASYNC_SID = 1;
+static const boost::uint16_t E100_FPGA_COMPAT_NUM = 11;
+static const boost::uint32_t E100_RX_SID_BASE = 30;
+static const boost::uint32_t E100_TX_ASYNC_SID = 10;
+static const boost::uint32_t E100_CTRL_MSG_SID = 20;
static const double E100_DEFAULT_CLOCK_RATE = 64e6;
+static const std::string E100_EEPROM_MAP_KEY = "E100";
//! load an fpga image from a bin file into the usrp-e fpga
extern void e100_load_fpga(const std::string &bin_file);
@@ -86,8 +88,8 @@ private:
uhd::property_tree::sptr _tree;
//controllers
- spi_core_100::sptr _fpga_spi_ctrl;
- i2c_core_100::sptr _fpga_i2c_ctrl;
+ fifo_ctrl_excelsior::sptr _fifo_ctrl;
+ i2c_core_200::sptr _fpga_i2c_ctrl;
rx_frontend_core_200::sptr _rx_fe;
tx_frontend_core_200::sptr _tx_fe;
std::vector<rx_dsp_core_200::sptr> _rx_dsps;
@@ -103,15 +105,12 @@ private:
//transports
uhd::transport::zero_copy_if::sptr _data_transport;
+ uhd::usrp::recv_packet_demuxer::sptr _recv_demuxer;
//dboard stuff
uhd::usrp::dboard_manager::sptr _dboard_manager;
uhd::usrp::dboard_iface::sptr _dboard_iface;
- //handle io stuff
- UHD_PIMPL_DECL(io_impl) _io_impl;
- void io_init(void);
-
//device properties interface
uhd::property_tree::sptr get_tree(void) const{
return _tree;
diff --git a/host/lib/usrp/e100/e100_mmap_zero_copy.cpp b/host/lib/usrp/e100/e100_mmap_zero_copy.cpp
index cdb7094f4..58beeb424 100644
--- a/host/lib/usrp/e100/e100_mmap_zero_copy.cpp
+++ b/host/lib/usrp/e100/e100_mmap_zero_copy.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -19,6 +19,7 @@
#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
@@ -41,23 +42,19 @@ public:
_mem(mem), _info(info) { /* NOP */ }
void release(void){
- if (_info->flags != RB_USER_PROCESS) return;
if (fp_verbose) UHD_LOGV(always) << "recv buff: release" << std::endl;
_info->flags = RB_KERNEL; //release the frame
}
- bool ready(void){return _info->flags & RB_USER;}
+ UHD_INLINE bool ready(void){return _info->flags & RB_USER;}
- sptr get_new(void){
- if (fp_verbose) UHD_LOGV(always) << " make_recv_buff: " << get_size() << std::endl;
+ 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_managed_buffer(this);
+ return make(this, _mem, _info->len);
}
private:
- const void *get_buff(void) const{return _mem;}
- size_t get_size(void) const{return _info->len;}
-
void *_mem;
ring_buffer_info *_info;
};
@@ -71,28 +68,24 @@ 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 commit(size_t len){
- if (_info->flags != RB_USER_PROCESS) return;
- if (fp_verbose) UHD_LOGV(always) << "send buff: commit " << len << std::endl;
- _info->len = len;
+ 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;
}
}
- bool ready(void){return _info->flags & RB_KERNEL;}
+ UHD_INLINE bool ready(void){return _info->flags & RB_KERNEL;}
- sptr get_new(void){
- if (fp_verbose) UHD_LOGV(always) << " make_send_buff: " << get_size() << std::endl;
+ 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_managed_buffer(this);
+ return make(this, _mem, _len);
}
private:
- void *get_buff(void) const{return _mem;}
- size_t get_size(void) const{return _len;}
-
void *_mem;
ring_buffer_info *_info;
size_t _len;
@@ -162,14 +155,14 @@ public:
//initialize the managed receive buffers
for (size_t i = 0; i < get_num_recv_frames(); i++){
- _mrb_pool.push_back(e100_mmap_zero_copy_mrb(
+ _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(e100_mmap_zero_copy_msb(
+ _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
));
@@ -183,7 +176,7 @@ public:
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];
+ e100_mmap_zero_copy_mrb &mrb = *_mrb_pool[_recv_index];
//poll/wait for a ready frame
if (not mrb.ready()){
@@ -215,7 +208,7 @@ public:
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];
+ e100_mmap_zero_copy_msb &msb = *_msb_pool[_send_index];
//poll/wait for a ready frame
if (not msb.ready()){
@@ -254,8 +247,8 @@ private:
size_t _frame_size, _map_size;
//re-usable managed buffers
- std::vector<e100_mmap_zero_copy_mrb> _mrb_pool;
- std::vector<e100_mmap_zero_copy_msb> _msb_pool;
+ 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;
diff --git a/host/lib/usrp/e100/e100_regs.hpp b/host/lib/usrp/e100/e100_regs.hpp
index 75be2cfbe..654163dce 100644
--- a/host/lib/usrp/e100/e100_regs.hpp
+++ b/host/lib/usrp/e100/e100_regs.hpp
@@ -15,55 +15,45 @@
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
-////////////////////////////////////////////////////////////////
-//
-// Memory map for embedded wishbone bus
-//
-////////////////////////////////////////////////////////////////
-
-// All addresses are byte addresses. All accesses are word (16-bit) accesses.
-// This means that address bit 0 is usually 0.
-// There are 11 bits of address for the control.
-
#ifndef INCLUDED_E100_REGS_HPP
#define INCLUDED_E100_REGS_HPP
-/////////////////////////////////////////////////////
-// Slave pointers
+#include <boost/cstdint.hpp>
-#define E100_REG_SLAVE(n) ((n)<<7)
+#define TOREG(x) ((x)*4)
-/////////////////////////////////////////////////////
-// Slave 0 -- Misc Regs
+#define localparam static const int
-#define E100_REG_MISC_BASE E100_REG_SLAVE(0)
+localparam SR_MISC = 0; // 5
+localparam SR_USER_REGS = 5; // 2
-#define E100_REG_MISC_LED E100_REG_MISC_BASE + 0
-#define E100_REG_MISC_SW E100_REG_MISC_BASE + 2
-#define E100_REG_MISC_CGEN_CTRL E100_REG_MISC_BASE + 4
-#define E100_REG_MISC_CGEN_ST E100_REG_MISC_BASE + 6
-#define E100_REG_MISC_TEST E100_REG_MISC_BASE + 8
-#define E100_REG_MISC_RX_LEN E100_REG_MISC_BASE + 10
-#define E100_REG_MISC_TX_LEN E100_REG_MISC_BASE + 12
-#define E100_REG_MISC_XFER_RATE E100_REG_MISC_BASE + 14
+localparam SR_TX_CTRL = 32; // 6
+localparam SR_TX_DSP = 40; // 5
+localparam SR_TX_FE = 48; // 5
-/////////////////////////////////////////////////////
-// Slave 1 -- UART
-// CLKDIV is 16 bits, others are only 8
+localparam SR_RX_CTRL0 = 96; // 9
+localparam SR_RX_DSP0 = 106; // 7
+localparam SR_RX_FE = 114; // 5
-#define E100_REG_UART_BASE E100_REG_SLAVE(1)
+localparam SR_RX_CTRL1 = 128; // 9
+localparam SR_RX_DSP1 = 138; // 7
-#define E100_REG_UART_CLKDIV E100_REG_UART_BASE + 0
-#define E100_REG_UART_TXLEVEL E100_REG_UART_BASE + 2
-#define E100_REG_UART_RXLEVEL E100_REG_UART_BASE + 4
-#define E100_REG_UART_TXCHAR E100_REG_UART_BASE + 6
-#define E100_REG_UART_RXCHAR E100_REG_UART_BASE + 8
+localparam SR_TIME64 = 192; // 6
+localparam SR_SPI = 208; // 3
+localparam SR_I2C = 216; // 1
+localparam SR_GPIO = 224; // 5
-/////////////////////////////////////////////////////
-// Slave 2 -- SPI Core
-//these are 32-bit registers mapped onto the 16-bit Wishbone bus.
-//Using peek32/poke32 should allow transparent use of these registers.
-#define E100_REG_SPI_BASE E100_REG_SLAVE(2)
+#define REG_RB_TIME_NOW_HI TOREG(10)
+#define REG_RB_TIME_NOW_LO TOREG(11)
+#define REG_RB_TIME_PPS_HI TOREG(14)
+#define REG_RB_TIME_PPS_LO TOREG(15)
+#define REG_RB_SPI TOREG(0)
+#define REG_RB_COMPAT TOREG(1)
+#define REG_RB_GPIO TOREG(3)
+#define REG_RB_I2C TOREG(2)
+#define REG_RB_CONFIG0 TOREG(4)
+#define REG_RB_CONFIG1 TOREG(5)
+#define REG_RB_NUM_RX_DSP TOREG(6)
//spi slave constants
#define UE_SPI_SS_AD9522 (1 << 3)
@@ -71,67 +61,5 @@
#define UE_SPI_SS_TX_DB (1 << 1)
#define UE_SPI_SS_RX_DB (1 << 0)
-////////////////////////////////////////////////
-// Slave 3 -- I2C Core
-
-#define E100_REG_I2C_BASE E100_REG_SLAVE(3)
-
-////////////////////////////////////////////////
-// Slave 5 -- Error messages buffer
-
-#define E100_REG_ERR_BUFF E100_REG_SLAVE(5)
-
-///////////////////////////////////////////////////
-// Slave 7 -- Readback Mux 32
-
-#define E100_REG_RB_MUX_32_BASE E100_REG_SLAVE(7)
-
-#define E100_REG_RB_TIME_NOW_HI E100_REG_RB_MUX_32_BASE + 0
-#define E100_REG_RB_TIME_NOW_LO E100_REG_RB_MUX_32_BASE + 4
-#define E100_REG_RB_TIME_PPS_HI E100_REG_RB_MUX_32_BASE + 8
-#define E100_REG_RB_TIME_PPS_LO E100_REG_RB_MUX_32_BASE + 12
-#define E100_REG_RB_MISC_TEST32 E100_REG_RB_MUX_32_BASE + 16
-#define E100_REG_RB_ERR_STATUS E100_REG_RB_MUX_32_BASE + 20
-#define E100_REG_RB_COMPAT E100_REG_RB_MUX_32_BASE + 24
-#define E100_REG_RB_GPIO E100_REG_RB_MUX_32_BASE + 28
-
-////////////////////////////////////////////////////
-// Slave 8 -- Settings Bus
-//
-// Output-only, no readback, 64 registers total
-// Each register must be written 64 bits at a time
-// First the address xxx_xx00 and then xxx_xx10
-
-// 64 total regs in address space
-#define UE_SR_RX_CTRL0 0 // 9 regs (+0 to +8)
-#define UE_SR_RX_DSP0 10 // 4 regs (+0 to +3)
-#define UE_SR_RX_CTRL1 16 // 9 regs (+0 to +8)
-#define UE_SR_RX_DSP1 26 // 4 regs (+0 to +3)
-#define UE_SR_ERR_CTRL 30 // 1 reg
-#define UE_SR_TX_CTRL 32 // 4 regs (+0 to +3)
-#define UE_SR_TX_DSP 38 // 3 regs (+0 to +2)
-
-#define UE_SR_TIME64 42 // 6 regs (+0 to +5)
-#define UE_SR_RX_FRONT 48 // 5 regs (+0 to +4)
-#define UE_SR_TX_FRONT 54 // 5 regs (+0 to +4)
-
-#define UE_SR_REG_TEST32 60 // 1 reg
-#define UE_SR_CLEAR_FIFO 61 // 1 reg
-#define UE_SR_GLOBAL_RESET 63 // 1 reg
-#define UE_SR_USER_REGS 64 // 2 regs
-
-#define UE_SR_GPIO 128
-
-#define E100_REG_SR_ADDR(n) (E100_REG_SLAVE(8) + (4*(n)))
-
-#define E100_REG_SR_MISC_TEST32 E100_REG_SR_ADDR(UE_SR_REG_TEST32)
-#define E100_REG_SR_ERR_CTRL E100_REG_SR_ADDR(UE_SR_ERR_CTRL)
-
-/////////////////////////////////////////////////
-// Magic reset regs
-////////////////////////////////////////////////
-#define E100_REG_CLEAR_FIFO E100_REG_SR_ADDR(UE_SR_CLEAR_FIFO)
-#define E100_REG_GLOBAL_RESET E100_REG_SR_ADDR(UE_SR_GLOBAL_RESET)
-
-#endif
+#endif /*INCLUDED_E100_REGS_HPP*/
diff --git a/host/lib/usrp/e100/include/linux/usrp_e.h b/host/lib/usrp/e100/include/linux/usrp_e.h
index 37e9ee31a..f0512a40c 100644
--- a/host/lib/usrp/e100/include/linux/usrp_e.h
+++ b/host/lib/usrp/e100/include/linux/usrp_e.h
@@ -1,6 +1,6 @@
/*
- * Copyright (C) 2010 Ettus Research, LLC
+ * Copyright (C) 2010-2012 Ettus Research, LLC
*
* Written by Philip Balister <philip@opensdr.com>
*
@@ -36,7 +36,7 @@ struct usrp_e_ctl32 {
#define USRP_E_GET_RB_INFO _IOR(USRP_E_IOC_MAGIC, 0x27, struct usrp_e_ring_buffer_size_t)
#define USRP_E_GET_COMPAT_NUMBER _IO(USRP_E_IOC_MAGIC, 0x28)
-#define USRP_E_COMPAT_NUMBER 3
+#define USRP_E_COMPAT_NUMBER 4
/* Flag defines */
#define RB_USER (1<<0)
diff --git a/host/lib/usrp/e100/io_impl.cpp b/host/lib/usrp/e100/io_impl.cpp
index 332fe76ae..4d521e222 100644
--- a/host/lib/usrp/e100/io_impl.cpp
+++ b/host/lib/usrp/e100/io_impl.cpp
@@ -15,27 +15,16 @@
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
-#include "recv_packet_demuxer.hpp"
#include "validate_subdev_spec.hpp"
#include "async_packet_handler.hpp"
#include "../../transport/super_recv_packet_handler.hpp"
#include "../../transport/super_send_packet_handler.hpp"
-#include <linux/usrp_e.h> //ioctl structures and constants
#include "e100_impl.hpp"
-#include "e100_regs.hpp"
#include <uhd/utils/msg.hpp>
#include <uhd/utils/log.hpp>
#include <uhd/utils/tasks.hpp>
-#include <uhd/utils/thread_priority.hpp>
-#include <uhd/transport/bounded_buffer.hpp>
#include <boost/bind.hpp>
#include <boost/format.hpp>
-#include <boost/bind.hpp>
-#include <boost/thread/thread.hpp>
-#include <poll.h> //poll
-#include <fcntl.h> //open, close
-#include <sstream>
-#include <fstream>
#include <boost/make_shared.hpp>
using namespace uhd;
@@ -44,134 +33,7 @@ using namespace uhd::transport;
static const size_t vrt_send_header_offset_words32 = 1;
-/***********************************************************************
- * io impl details (internal to this file)
- * - pirate crew of 1
- * - bounded buffer
- * - thread loop
- * - vrt packet handler states
- **********************************************************************/
-struct e100_impl::io_impl{
- io_impl(void):
- false_alarm(0), async_msg_fifo(1000/*messages deep*/)
- { /* NOP */ }
-
- double tick_rate; //set by update tick rate method
- e100_ctrl::sptr iface; //so handle irq can peek and poke
- void handle_irq(void);
- size_t false_alarm;
- //The data transport is listed first so that it is deconstructed last,
- //which is after the states and booty which may hold managed buffers.
- recv_packet_demuxer::sptr demuxer;
-
- //a pirate's life is the life for me!
- void recv_pirate_loop(
- spi_iface::sptr //keep a sptr to iface which shares gpio147
- ){
- //open the GPIO and set it up for an IRQ
- std::ofstream edge_file("/sys/class/gpio/gpio147/edge");
- edge_file << "rising" << std::endl << std::flush;
- edge_file.close();
- int fd = ::open("/sys/class/gpio/gpio147/value", O_RDONLY);
- if (fd < 0) UHD_MSG(error) << "Unable to open GPIO for IRQ\n";
-
- while (not boost::this_thread::interruption_requested()){
- pollfd pfd;
- pfd.fd = fd;
- pfd.events = POLLPRI | POLLERR;
- ssize_t ret = ::poll(&pfd, 1, 100/*ms*/);
- if (ret > 0) this->handle_irq();
- }
-
- //cleanup before thread exit
- ::close(fd);
- }
- bounded_buffer<async_metadata_t> async_msg_fifo;
- task::sptr pirate_task;
-};
-
-void e100_impl::io_impl::handle_irq(void){
- //check the status of the async msg buffer
- const boost::uint32_t status = iface->peek32(E100_REG_RB_ERR_STATUS);
- if ((status & 0x3) == 0){ //not done or error
- //This could be a false-alarm because spi readback is mixed in.
- //So we just sleep for a bit rather than interrupt continuously.
- if (false_alarm++ > 3) boost::this_thread::sleep(boost::posix_time::milliseconds(1));
- return;
- }
- false_alarm = 0; //its a real message, reset the count...
- //std::cout << boost::format("status: 0x%x") % status << std::endl;
-
- //load the data struct and call the ioctl
- usrp_e_ctl32 data;
- data.offset = E100_REG_ERR_BUFF;
- data.count = status >> 16;
- iface->ioctl(USRP_E_READ_CTL32, &data);
- //for (size_t i = 0; i < data.count; i++){
- //data.buf[i] = iface->peek32(E100_REG_ERR_BUFF + i*sizeof(boost::uint32_t));
- //std::cout << boost::format(" buff[%u] = 0x%08x\n") % i % data.buf[i];
- //}
-
- //unpack the vrt header and process below...
- vrt::if_packet_info_t if_packet_info;
- if_packet_info.num_packet_words32 = data.count;
- try{vrt::if_hdr_unpack_le(data.buf, if_packet_info);}
- catch(const std::exception &e){
- UHD_MSG(error) << "Error unpacking vrt header:\n" << e.what() << std::endl;
- goto prepare;
- }
-
- //handle a tx async report message
- if (if_packet_info.sid == E100_TX_ASYNC_SID and if_packet_info.packet_type != vrt::if_packet_info_t::PACKET_TYPE_DATA){
-
- //fill in the async metadata
- async_metadata_t metadata;
- load_metadata_from_buff(uhd::wtohx<boost::uint32_t>, metadata, if_packet_info, data.buf, tick_rate);
-
- //push the message onto the queue
- async_msg_fifo.push_with_pop_on_full(metadata);
-
- //print some fastpath messages
- standard_async_msg_prints(metadata);
- }
-
- //prepare for the next round
- prepare:
- iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 0); //clear
- while ((iface->peek32(E100_REG_RB_ERR_STATUS) & (1 << 2)) == 0){} //wait for idle
- iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 1); //start
-}
-
-/***********************************************************************
- * Helper Functions
- **********************************************************************/
-void e100_impl::io_init(void){
-
- //create new io impl
- _io_impl = UHD_PIMPL_MAKE(io_impl, ());
- _io_impl->demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), E100_RX_SID_BASE);
- _io_impl->iface = _fpga_ctrl;
-
- //clear fifo state machines
- _fpga_ctrl->poke32(E100_REG_CLEAR_FIFO, 0);
-
- //allocate streamer weak ptrs containers
- _rx_streamers.resize(_rx_dsps.size());
- _tx_streamers.resize(1/*known to be 1 dsp*/);
-
- //prepare the async msg buffer for incoming messages
- _fpga_ctrl->poke32(E100_REG_SR_ERR_CTRL, 1 << 0); //clear
- while ((_fpga_ctrl->peek32(E100_REG_RB_ERR_STATUS) & (1 << 2)) == 0){} //wait for idle
- _fpga_ctrl->poke32(E100_REG_SR_ERR_CTRL, 1 << 1); //start
-
- //spawn a pirate, yarrr!
- _io_impl->pirate_task = task::make(boost::bind(
- &e100_impl::io_impl::recv_pirate_loop, _io_impl.get(), _aux_spi_iface
- ));
-}
-
void e100_impl::update_tick_rate(const double rate){
- _io_impl->tick_rate = rate;
//update the tick rate on all existing streamers -> thread safe
for (size_t i = 0; i < _rx_streamers.size(); i++){
@@ -254,8 +116,7 @@ void e100_impl::update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){
bool e100_impl::recv_async_msg(
async_metadata_t &async_metadata, double timeout
){
- boost::this_thread::disable_interruption di; //disable because the wait can throw
- return _io_impl->async_msg_fifo.pop_with_timed_wait(async_metadata, timeout);
+ return _fifo_ctrl->pop_async_msg(async_metadata, timeout);
}
/***********************************************************************
@@ -300,7 +161,7 @@ rx_streamer::sptr e100_impl::get_rx_stream(const uhd::stream_args_t &args_){
_rx_dsps[dsp]->set_nsamps_per_packet(spp); //seems to be a good place to set this
_rx_dsps[dsp]->setup(args);
my_streamer->set_xport_chan_get_buff(chan_i, boost::bind(
- &recv_packet_demuxer::get_recv_buff, _io_impl->demuxer, dsp, _1
+ &recv_packet_demuxer::get_recv_buff, _recv_demuxer, dsp, _1
), true /*flush*/);
my_streamer->set_overflow_handler(chan_i, boost::bind(
&rx_dsp_core_200::handle_overflow, _rx_dsps[dsp]
diff --git a/host/lib/usrp/mboard_eeprom.cpp b/host/lib/usrp/mboard_eeprom.cpp
index 785d30296..1f4abc27e 100644
--- a/host/lib/usrp/mboard_eeprom.cpp
+++ b/host/lib/usrp/mboard_eeprom.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -84,17 +84,20 @@ static std::string uint16_bytes_to_string(const byte_vector_t &bytes){
**********************************************************************/
static const boost::uint8_t N100_EEPROM_ADDR = 0x50;
-static const uhd::dict<std::string, boost::uint8_t> USRP_N100_OFFSETS = boost::assign::map_list_of
- ("hardware", 0x00)
- ("mac-addr", 0x02)
- ("ip-addr", 0x0C)
- //leave space here for other addresses (perhaps)
- ("revision", 0x12)
- ("product", 0x14)
- ("gpsdo", 0x17)
- ("serial", 0x18)
- ("name", 0x18 + SERIAL_LEN)
-;
+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,
@@ -105,30 +108,36 @@ enum n200_gpsdo_type{
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, USRP_N100_OFFSETS["hardware"], 2)
+ 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, USRP_N100_OFFSETS["revision"], 2)
+ 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, USRP_N100_OFFSETS["product"], 2)
+ 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, USRP_N100_OFFSETS["mac-addr"], 6
+ 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, USRP_N100_OFFSETS["ip-addr"], 4), 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, USRP_N100_OFFSETS["gpsdo"], 1).at(0);
+ 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;
@@ -137,12 +146,12 @@ static void load_n100(mboard_eeprom_t &mb_eeprom, i2c_iface &iface){
//extract the serial
mb_eeprom["serial"] = bytes_to_string(iface.read_eeprom(
- N100_EEPROM_ADDR, USRP_N100_OFFSETS["serial"], SERIAL_LEN
+ 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, USRP_N100_OFFSETS["name"], NAME_MAX_LEN
+ N100_EEPROM_ADDR, offsetof(n100_eeprom_map, name), NAME_MAX_LEN
));
//Empty serial correction: use the mac address to determine serial.
@@ -158,32 +167,44 @@ static void load_n100(mboard_eeprom_t &mb_eeprom, i2c_iface &iface){
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, USRP_N100_OFFSETS["hardware"],
+ 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, USRP_N100_OFFSETS["revision"],
+ 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, USRP_N100_OFFSETS["product"],
+ 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, USRP_N100_OFFSETS["mac-addr"],
+ 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, USRP_N100_OFFSETS["ip-addr"], 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
@@ -191,18 +212,18 @@ static void store_n100(const mboard_eeprom_t &mb_eeprom, i2c_iface &iface){
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, USRP_N100_OFFSETS["gpsdo"], byte_vector_t(1, gpsdo_byte));
+ 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, USRP_N100_OFFSETS["serial"],
+ 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, USRP_N100_OFFSETS["name"],
+ N100_EEPROM_ADDR, offsetof(n100_eeprom_map, name),
string_to_bytes(mb_eeprom["name"], NAME_MAX_LEN)
);
}
@@ -426,20 +447,16 @@ mboard_eeprom_t::mboard_eeprom_t(void){
/* NOP */
}
-mboard_eeprom_t::mboard_eeprom_t(i2c_iface &iface, map_type map){
- switch(map){
- case MAP_N100: load_n100(*this, iface); break;
- case MAP_B000: load_b000(*this, iface); break;
- case MAP_B100: load_b100(*this, iface); break;
- case MAP_E100: load_e100(*this, iface); break;
- }
+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, map_type map) const{
- switch(map){
- case MAP_N100: store_n100(*this, iface); break;
- case MAP_B000: store_b000(*this, iface); break;
- case MAP_B100: store_b100(*this, iface); break;
- case MAP_E100: store_e100(*this, iface); break;
- }
+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
index 93c0eada6..0331cf93a 100644
--- a/host/lib/usrp/multi_usrp.cpp
+++ b/host/lib/usrp/multi_usrp.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -21,6 +21,10 @@
#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>
@@ -125,6 +129,9 @@ static tune_result_t tune_xx_subdev_and_dsp(
//------------------------------------------------------------------
double lo_offset = 0.0;
if (rf_fe_subtree->access<bool>("use_lo_offset").get()){
+ //If the frontend has lo_offset value and range properties, trust it for lo_offset
+ if (rf_fe_subtree->exists("lo_offset/value")) lo_offset = rf_fe_subtree->access<double>("lo_offset/value").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();
@@ -143,6 +150,14 @@ static tune_result_t tune_xx_subdev_and_dsp(
break;
case tune_request_t::POLICY_MANUAL:
+ //If the rf_fe understands lo_offset settings, infer the desired lo_offset and set it
+ // Side effect: In TVRX2 for example, after setting the lo_offset (if_freq) with a
+ // POLICY_MANUAL, there is no way for the user to automatically get back to default
+ // if_freq without deconstruct/reconstruct the rf_fe objects.
+ if (rf_fe_subtree->exists("lo_offset/value")) {
+ rf_fe_subtree->access<double>("lo_offset/value").set(tune_request.rf_freq - tune_request.target_freq);
+ }
+
target_rf_freq = tune_request.rf_freq;
rf_fe_subtree->access<double>("freq/value").set(target_rf_freq);
break;
@@ -214,6 +229,44 @@ public:
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
******************************************************************/
@@ -356,12 +409,27 @@ public:
return true;
}
- void set_command_time(const time_spec_t &, size_t){
- throw uhd::not_implemented_error("Not implemented yet, but we have a very good idea of how to do it.");
+ 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){
- throw uhd::not_implemented_error("Not implemented yet, but we have a very good idea of how to do it.");
+ 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){
@@ -522,6 +590,10 @@ public:
);
}
+ 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);
}
@@ -621,10 +693,6 @@ public:
return _tree->access<subdev_spec_t>(mb_root(mboard) / "tx_subdev_spec").get();
}
- std::string get_tx_subdev_name(size_t chan){
- return _tree->access<std::string>(tx_rf_fe_root(chan) / "name").get();
- }
-
size_t get_tx_num_channels(void){
size_t sum = 0;
for (size_t m = 0; m < get_num_mboards(); m++){
@@ -633,6 +701,10 @@ public:
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);
@@ -670,6 +742,10 @@ public:
);
}
+ 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);
}
@@ -832,7 +908,7 @@ private:
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 */);
+ gg->register_fcns("DAC-"+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 */);
diff --git a/host/lib/usrp/usrp1/codec_ctrl.cpp b/host/lib/usrp/usrp1/codec_ctrl.cpp
index c82569ea3..7383c9833 100644
--- a/host/lib/usrp/usrp1/codec_ctrl.cpp
+++ b/host/lib/usrp/usrp1/codec_ctrl.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -27,6 +27,7 @@
#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>
@@ -375,6 +376,12 @@ double usrp1_codec_ctrl_impl::fine_tune(double codec_rate, double target_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);
diff --git a/host/lib/usrp/usrp1/io_impl.cpp b/host/lib/usrp/usrp1/io_impl.cpp
index b5575ef8f..8940a92bb 100644
--- a/host/lib/usrp/usrp1/io_impl.cpp
+++ b/host/lib/usrp/usrp1/io_impl.cpp
@@ -90,8 +90,8 @@ public:
/* NOP */
}
- void commit(size_t size){
- if (size != 0) this->_commit_cb(_curr_buff, _next_buff, size);
+ void release(void){
+ this->_commit_cb(_curr_buff, _next_buff, size());
}
sptr get_new(
@@ -100,13 +100,13 @@ public:
){
_curr_buff = curr_buff;
_next_buff = next_buff;
- return make_managed_buffer(this);
+ return make(this,
+ _curr_buff.buff->cast<char *>() + _curr_buff.offset,
+ _curr_buff.buff->size() - _curr_buff.offset
+ );
}
private:
- void *get_buff(void) const{return _curr_buff.buff->cast<char *>() + _curr_buff.offset;}
- size_t get_size(void) const{return _curr_buff.buff->size() - _curr_buff.offset;}
-
offset_send_buffer _curr_buff, _next_buff;
commit_cb_type _commit_cb;
};
diff --git a/host/lib/usrp/usrp1/usrp1_impl.cpp b/host/lib/usrp/usrp1/usrp1_impl.cpp
index 96570d019..253ac1d6f 100644
--- a/host/lib/usrp/usrp1/usrp1_impl.cpp
+++ b/host/lib/usrp/usrp1/usrp1_impl.cpp
@@ -84,11 +84,7 @@ static device_addrs_t usrp1_find(const device_addr_t &hint)
usrp1_fw_image = find_image_path(hint.get("fw", "usrp1_fw.ihx"));
}
catch(...){
- UHD_MSG(warning) << boost::format(
- "Could not locate USRP1 firmware.\n"
- "Please install the images package.\n"
- );
- return usrp1_addrs;
+ UHD_MSG(warning) << boost::format("Could not locate USRP1 firmware. %s") % print_images_error();
}
UHD_LOG << "USRP1 firmware image: " << usrp1_fw_image << std::endl;
@@ -116,7 +112,7 @@ static device_addrs_t usrp1_find(const device_addr_t &hint)
catch(const uhd::exception &){continue;} //ignore claimed
fx2_ctrl::sptr fx2_ctrl = fx2_ctrl::make(control);
- const mboard_eeprom_t mb_eeprom(*fx2_ctrl, mboard_eeprom_t::MAP_B000);
+ 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"];
@@ -209,14 +205,20 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){
_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 (Classic)");
+ _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));
////////////////////////////////////////////////////////////////////
+ // create user-defined control objects
+ ////////////////////////////////////////////////////////////////////
+ _tree->create<std::pair<boost::uint8_t, boost::uint32_t> >(mb_path / "user" / "regs")
+ .subscribe(boost::bind(&usrp1_impl::set_reg, this, _1));
+
+ ////////////////////////////////////////////////////////////////////
// setup the mboard eeprom
////////////////////////////////////////////////////////////////////
- const mboard_eeprom_t mb_eeprom(*_fx2_ctrl, mboard_eeprom_t::MAP_B000);
+ 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));
@@ -353,6 +355,9 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){
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));
+ //disable rx dc offset if LFRX
+ if (rx_db_eeprom.id == 0x000f) _tree->access<bool>(mb_path / "rx_frontends" / db / "dc_offset" / "enable").set(false);
+
//create the properties and register subscribers
_tree->create<dboard_eeprom_t>(mb_path / "dboards" / db/ "rx_eeprom")
.set(rx_db_eeprom)
@@ -447,7 +452,7 @@ bool usrp1_impl::has_tx_halfband(void){
* Properties callback methods below
**********************************************************************/
void usrp1_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){
- mb_eeprom.commit(*_fx2_ctrl, mboard_eeprom_t::MAP_B000);
+ 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){
@@ -496,3 +501,8 @@ std::complex<double> usrp1_impl::set_rx_dc_offset(const std::string &db, const s
return std::complex<double>(double(i_off) * (1ul << 31), double(q_off) * (1ul << 31));
}
+
+void usrp1_impl::set_reg(const std::pair<boost::uint8_t, boost::uint32_t> &reg)
+{
+ _iface->poke32(reg.first, reg.second);
+}
diff --git a/host/lib/usrp/usrp1/usrp1_impl.hpp b/host/lib/usrp/usrp1/usrp1_impl.hpp
index d903a18e9..0be8ebca9 100644
--- a/host/lib/usrp/usrp1/usrp1_impl.hpp
+++ b/host/lib/usrp/usrp1/usrp1_impl.hpp
@@ -38,6 +38,8 @@
#ifndef INCLUDED_USRP1_IMPL_HPP
#define INCLUDED_USRP1_IMPL_HPP
+static const std::string USRP1_EEPROM_MAP_KEY = "B000";
+
#define FR_RB_CAPS 3
#define FR_MODE 13
#define FR_DEBUG_EN 14
@@ -152,6 +154,8 @@ private:
void vandal_conquest_loop(void);
+ void set_reg(const std::pair<boost::uint8_t, boost::uint32_t> &reg);
+
//handle the enables
bool _rx_enabled, _tx_enabled;
void enable_rx(bool enb){
diff --git a/host/lib/usrp/usrp2/CMakeLists.txt b/host/lib/usrp/usrp2/CMakeLists.txt
index 10f7407b0..da39d9df1 100644
--- a/host/lib/usrp/usrp2/CMakeLists.txt
+++ b/host/lib/usrp/usrp2/CMakeLists.txt
@@ -1,5 +1,5 @@
#
-# Copyright 2011 Ettus Research LLC
+# Copyright 2011-2012 Ettus Research LLC
#
# This program is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
@@ -32,5 +32,6 @@ IF(ENABLE_USRP2)
${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
index b2912c70c..0ae3b0bd8 100644
--- a/host/lib/usrp/usrp2/clock_ctrl.cpp
+++ b/host/lib/usrp/usrp2/clock_ctrl.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -35,8 +35,9 @@ static const bool enb_test_clk = false;
*/
class usrp2_clock_ctrl_impl : public usrp2_clock_ctrl{
public:
- usrp2_clock_ctrl_impl(usrp2_iface::sptr iface){
+ 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;
@@ -331,7 +332,7 @@ private:
*/
void write_reg(boost::uint8_t addr){
boost::uint32_t data = _ad9510_regs.get_write_reg(addr);
- _iface->write_spi(SPI_SS_AD9510, spi_config_t::EDGE_RISE, data, 24);
+ _spiface->write_spi(SPI_SS_AD9510, spi_config_t::EDGE_RISE, data, 24);
}
/*!
@@ -377,7 +378,7 @@ private:
}
usrp2_iface::sptr _iface;
-
+ uhd::spi_iface::sptr _spiface;
usrp2_clk_regs_t clk_regs;
ad9510_regs_t _ad9510_regs;
};
@@ -385,6 +386,6 @@ private:
/***********************************************************************
* Public make function for the ad9510 clock control
**********************************************************************/
-usrp2_clock_ctrl::sptr usrp2_clock_ctrl::make(usrp2_iface::sptr iface){
- return sptr(new usrp2_clock_ctrl_impl(iface));
+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
index 9ccbc959e..067e1e35d 100644
--- a/host/lib/usrp/usrp2/clock_ctrl.hpp
+++ b/host/lib/usrp/usrp2/clock_ctrl.hpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010 Ettus Research LLC
+// 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
@@ -29,10 +29,11 @@ public:
/*!
* Make a clock config for the ad9510 ic.
- * \param _iface a pointer to the usrp2 interface object
+ * \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);
+ static sptr make(usrp2_iface::sptr iface, uhd::spi_iface::sptr spiface);
/*!
* Get the master clock frequency for the fpga.
diff --git a/host/lib/usrp/usrp2/codec_ctrl.cpp b/host/lib/usrp/usrp2/codec_ctrl.cpp
index 06bf83b15..b53c4d9df 100644
--- a/host/lib/usrp/usrp2/codec_ctrl.cpp
+++ b/host/lib/usrp/usrp2/codec_ctrl.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -32,8 +32,9 @@ using namespace uhd;
*/
class usrp2_codec_ctrl_impl : public usrp2_codec_ctrl{
public:
- usrp2_codec_ctrl_impl(usrp2_iface::sptr iface){
+ 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;
@@ -189,11 +190,12 @@ 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;
- _iface->write_spi(
+ _spiface->write_spi(
SPI_SS_AD9777, spi_config_t::EDGE_RISE,
reg, 16
);
@@ -201,7 +203,7 @@ private:
void send_ads62p44_reg(boost::uint8_t addr) {
boost::uint16_t reg = _ads62p44_regs.get_write_reg(addr);
- _iface->write_spi(
+ _spiface->write_spi(
SPI_SS_ADS62P44, spi_config_t::EDGE_FALL,
reg, 16
);
@@ -211,6 +213,6 @@ private:
/***********************************************************************
* Public make function for the usrp2 codec control
**********************************************************************/
-usrp2_codec_ctrl::sptr usrp2_codec_ctrl::make(usrp2_iface::sptr iface){
- return sptr(new usrp2_codec_ctrl_impl(iface));
+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
index ca300e2b1..b0d815be2 100644
--- a/host/lib/usrp/usrp2/codec_ctrl.hpp
+++ b/host/lib/usrp/usrp2/codec_ctrl.hpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -28,10 +28,11 @@ public:
/*!
* Make a codec control for the DAC and ADC.
- * \param _iface a pointer to the usrp2 interface object
+ * \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);
+ static sptr make(usrp2_iface::sptr iface, uhd::spi_iface::sptr spiface);
/*!
* Set the modulation mode for the DAC.
diff --git a/host/lib/usrp/usrp2/dboard_iface.cpp b/host/lib/usrp/usrp2/dboard_iface.cpp
index bc510c8a1..edd9ef242 100644
--- a/host/lib/usrp/usrp2/dboard_iface.cpp
+++ b/host/lib/usrp/usrp2/dboard_iface.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -16,7 +16,7 @@
//
#include "gpio_core_200.hpp"
-#include "usrp2_iface.hpp"
+#include <uhd/types/serial.hpp>
#include "clock_ctrl.hpp"
#include "usrp2_regs.hpp" //wishbone address constants
#include <uhd/usrp/dboard_iface.hpp>
@@ -35,7 +35,12 @@ using namespace boost::assign;
class usrp2_dboard_iface : public dboard_iface{
public:
- usrp2_dboard_iface(usrp2_iface::sptr iface, usrp2_clock_ctrl::sptr clock_ctrl);
+ 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){
@@ -79,7 +84,8 @@ public:
);
private:
- usrp2_iface::sptr _iface;
+ uhd::i2c_iface::sptr _i2c_iface;
+ uhd::spi_iface::sptr _spi_iface;
usrp2_clock_ctrl::sptr _clock_ctrl;
gpio_core_200::sptr _gpio;
@@ -92,22 +98,28 @@ private:
* Make Function
**********************************************************************/
dboard_iface::sptr make_usrp2_dboard_iface(
- usrp2_iface::sptr 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(iface, 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(
- usrp2_iface::sptr iface,
+ wb_iface::sptr wb_iface,
+ uhd::i2c_iface::sptr i2c_iface,
+ uhd::spi_iface::sptr spi_iface,
usrp2_clock_ctrl::sptr clock_ctrl
-){
- _iface = iface;
- _clock_ctrl = clock_ctrl;
- _gpio = gpio_core_200::make(_iface, U2_REG_SR_ADDR(SR_GPIO), U2_REG_GPIO_RB);
+):
+ _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();
@@ -202,7 +214,7 @@ void usrp2_dboard_iface::write_spi(
boost::uint32_t data,
size_t num_bits
){
- _iface->write_spi(unit_to_spi_dev[unit], config, data, num_bits);
+ _spi_iface->write_spi(unit_to_spi_dev[unit], config, data, num_bits);
}
boost::uint32_t usrp2_dboard_iface::read_write_spi(
@@ -211,18 +223,18 @@ boost::uint32_t usrp2_dboard_iface::read_write_spi(
boost::uint32_t data,
size_t num_bits
){
- return _iface->read_spi(unit_to_spi_dev[unit], config, data, 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 _iface->write_i2c(addr, 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 _iface->read_i2c(addr, num_bytes);
+ return _i2c_iface->read_i2c(addr, num_bytes);
}
/***********************************************************************
@@ -233,7 +245,7 @@ void usrp2_dboard_iface::_write_aux_dac(unit_t unit){
(UNIT_RX, SPI_SS_RX_DAC)
(UNIT_TX, SPI_SS_TX_DAC)
;
- _iface->write_spi(
+ _spi_iface->write_spi(
unit_to_spi_dac[unit], spi_config_t::EDGE_FALL,
_dac_regs[unit].get_reg(), 24
);
@@ -281,11 +293,11 @@ double usrp2_dboard_iface::read_aux_adc(unit_t unit, aux_adc_t which){
} ad7922_regs.chn = ad7922_regs.mod; //normal mode: mod == chn
//write and read spi
- _iface->write_spi(
+ _spi_iface->write_spi(
unit_to_spi_adc[unit], config,
ad7922_regs.get_reg(), 16
);
- ad7922_regs.set_reg(boost::uint16_t(_iface->read_spi(
+ ad7922_regs.set_reg(boost::uint16_t(_spi_iface->read_spi(
unit_to_spi_adc[unit], config,
ad7922_regs.get_reg(), 16
)));
diff --git a/host/lib/usrp/usrp2/fw_common.h b/host/lib/usrp/usrp2/fw_common.h
index 0babf7445..7e3de1497 100644
--- a/host/lib/usrp/usrp2/fw_common.h
+++ b/host/lib/usrp/usrp2/fw_common.h
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -30,13 +30,20 @@ extern "C" {
#endif
//fpga and firmware compatibility numbers
-#define USRP2_FPGA_COMPAT_NUM 9
-#define USRP2_FW_COMPAT_NUM 11
-#define USRP2_FW_VER_MINOR 2
+#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
@@ -44,12 +51,14 @@ extern "C" {
#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
////////////////////////////////////////////////////////////////////////
@@ -65,6 +74,8 @@ extern "C" {
////////////////////////////////////////////////////////////////////////
#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
diff --git a/host/lib/usrp/usrp2/io_impl.cpp b/host/lib/usrp/usrp2/io_impl.cpp
index d32ffb62c..e06cf8f6f 100644
--- a/host/lib/usrp/usrp2/io_impl.cpp
+++ b/host/lib/usrp/usrp2/io_impl.cpp
@@ -21,6 +21,7 @@
#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>
@@ -31,6 +32,7 @@
#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>
@@ -361,6 +363,61 @@ bool usrp2_impl::recv_async_msg(
}
/***********************************************************************
+ * 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));
+ send_buff.reset();
+ 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_){
@@ -406,6 +463,7 @@ rx_streamer::sptr usrp2_impl::get_rx_stream(const uhd::stream_args_t &args_){
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*/);
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
index 123910166..8804433e7 100644
--- a/host/lib/usrp/usrp2/usrp2_iface.cpp
+++ b/host/lib/usrp/usrp2/usrp2_iface.cpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -16,11 +16,13 @@
//
#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>
@@ -31,12 +33,14 @@
#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;
@@ -105,7 +109,7 @@ public:
throw uhd::runtime_error("firmware not responding");
_protocol_compat = ntohl(ctrl_data.proto_ver);
- mb_eeprom = mboard_eeprom_t(*this, mboard_eeprom_t::MAP_N100);
+ mb_eeprom = mboard_eeprom_t(*this, USRP2_EEPROM_MAP_KEY);
}
~usrp2_iface_impl(void){UHD_SAFE_CALL(
@@ -118,12 +122,12 @@ public:
void lock_device(bool lock){
if (lock){
- this->get_reg<boost::uint32_t, USRP2_REG_ACTION_FW_POKE32>(U2_FW_REG_LOCK_GPID, boost::uint32_t(get_gpid()));
+ 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->get_reg<boost::uint32_t, USRP2_REG_ACTION_FW_POKE32>(U2_FW_REG_LOCK_TIME, 0); //unlock
+ this->pokefw(U2_FW_REG_LOCK_TIME, 0); //unlock
}
}
@@ -131,8 +135,8 @@ public:
//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->get_reg<boost::uint32_t, USRP2_REG_ACTION_FW_PEEK32>(U2_FW_REG_LOCK_TIME);
- boost::uint32_t lock_gpid = this->get_reg<boost::uint32_t, USRP2_REG_ACTION_FW_PEEK32>(U2_FW_REG_LOCK_GPID);
+ 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);
@@ -148,7 +152,7 @@ public:
void lock_task(void){
//re-lock in task
- this->get_reg<boost::uint32_t, USRP2_REG_ACTION_FW_POKE32>(U2_FW_REG_LOCK_TIME, this->get_curr_time());
+ this->pokefw(U2_FW_REG_LOCK_TIME, this->get_curr_time());
//sleep for a bit
boost::this_thread::sleep(boost::posix_time::milliseconds(1500));
}
@@ -176,6 +180,16 @@ public:
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
@@ -311,8 +325,10 @@ public:
"\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."
- ) % ((lo == hi)? (boost::format("%d") % hi) : (boost::format("[%d to %d]") % lo % hi)) % compat));
+ "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;
@@ -340,13 +356,13 @@ public:
const std::string get_cname(void){
switch(this->get_rev()){
- case USRP2_REV3: return "USRP2-REV3";
- case USRP2_REV4: return "USRP2-REV4";
- case USRP_N200: return "USRP-N200";
- case USRP_N210: return "USRP-N210";
- case USRP_N200_R4: return "USRP-N200-REV4";
- case USRP_N210_R4: return "USRP-N210-REV4";
- case USRP_NXXX: return "USRP-N???";
+ 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();
}
@@ -356,6 +372,58 @@ public:
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 burner commands
+ 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_path = (fs::path(fw_image_path).branch_path().branch_path() / "utils" / "usrp_n2xx_simple_net_burner").string();
+ const std::string net_burner_cmd = str(boost::format("\"%s\" %s--addr=\"%s\"") % net_burner_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;
diff --git a/host/lib/usrp/usrp2/usrp2_iface.hpp b/host/lib/usrp/usrp2/usrp2_iface.hpp
index 9aa1a16aa..ed4de02d5 100644
--- a/host/lib/usrp/usrp2/usrp2_iface.hpp
+++ b/host/lib/usrp/usrp2/usrp2_iface.hpp
@@ -1,5 +1,5 @@
//
-// Copyright 2010-2011 Ettus Research LLC
+// 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
@@ -43,6 +43,12 @@ public:
*/
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,
@@ -69,6 +75,9 @@ public:
//! 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;
};
diff --git a/host/lib/usrp/usrp2/usrp2_impl.cpp b/host/lib/usrp/usrp2/usrp2_impl.cpp
index e6e8ca675..21f166aa1 100644
--- a/host/lib/usrp/usrp2/usrp2_impl.cpp
+++ b/host/lib/usrp/usrp2/usrp2_impl.cpp
@@ -368,8 +368,9 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
"\nPlease update the firmware and FPGA images for your device.\n"
"See the application notes for USRP2/N-Series for instructions.\n"
"Expected FPGA compatibility number %d, but got %d:\n"
- "The FPGA build is not compatible with the host code build."
- ) % int(USRP2_FPGA_COMPAT_NUM) % fpga_major));
+ "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));
@@ -391,8 +392,28 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
_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_TX_DSP0_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
@@ -404,7 +425,7 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
////////////////////////////////////////////////////////////////
// create clock control objects
////////////////////////////////////////////////////////////////
- _mbc[mb].clock = usrp2_clock_ctrl::make(_mbc[mb].iface);
+ _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));
@@ -416,7 +437,7 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
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].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:
@@ -442,19 +463,48 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
}
_tree->create<std::string>(tx_codec_path / "name").set("ad9777");
- ////////////////////////////////////////////////////////////////
- // create gpsdo control objects
- ////////////////////////////////////////////////////////////////
- if (_mbc[mb].iface->mb_eeprom["gpsdo"] == "internal"){
- _mbc[mb].gps = gps_ctrl::make(udp_simple::make_uart(udp_simple::make_connected(
- addr, BOOST_STRINGIZE(USRP2_UDP_UART_GPS_PORT)
- )));
- if(_mbc[mb].gps->gps_detected()) {
- BOOST_FOREACH(const std::string &name, _mbc[mb].gps->get_sensors()){
+ ////////////////////////////////////////////////////////////////////
+ // 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);
+ }
}
////////////////////////////////////////////////////////////////
@@ -469,10 +519,10 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
// create frontend control objects
////////////////////////////////////////////////////////////////
_mbc[mb].rx_fe = rx_frontend_core_200::make(
- _mbc[mb].iface, U2_REG_SR_ADDR(SR_RX_FRONT)
+ _mbc[mb].wbiface, U2_REG_SR_ADDR(SR_RX_FRONT)
);
_mbc[mb].tx_fe = tx_frontend_core_200::make(
- _mbc[mb].iface, U2_REG_SR_ADDR(SR_TX_FRONT)
+ _mbc[mb].wbiface, U2_REG_SR_ADDR(SR_TX_FRONT)
);
_tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec")
@@ -503,10 +553,10 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
// create rx dsp control objects
////////////////////////////////////////////////////////////////
_mbc[mb].rx_dsps.push_back(rx_dsp_core_200::make(
- _mbc[mb].iface, U2_REG_SR_ADDR(SR_RX_DSP0), U2_REG_SR_ADDR(SR_RX_CTRL0), USRP2_RX_SID_BASE + 0, true
+ _mbc[mb].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].iface, U2_REG_SR_ADDR(SR_RX_DSP1), U2_REG_SR_ADDR(SR_RX_CTRL1), USRP2_RX_SID_BASE + 1, true
+ _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);
@@ -531,7 +581,7 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
// create tx dsp control objects
////////////////////////////////////////////////////////////////
_mbc[mb].tx_dsp = tx_dsp_core_200::make(
- _mbc[mb].iface, U2_REG_SR_ADDR(SR_TX_DSP), U2_REG_SR_ADDR(SR_TX_CTRL), USRP2_TX_ASYNC_SID
+ _mbc[mb].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")
@@ -565,7 +615,7 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
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].iface, U2_REG_SR_ADDR(SR_TIME64), time64_rb_bases, mimo_clock_sync_delay_cycles
+ _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));
@@ -583,13 +633,26 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
//setup reference source props
_tree->create<std::string>(mb_path / "clock_source/value")
.subscribe(boost::bind(&usrp2_impl::update_clock_source, this, mb, _1));
- static const std::vector<std::string> clock_sources = boost::assign::list_of("internal")("external")("mimo");
+ 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].iface, U2_REG_SR_ADDR(SR_USER_REGS));
+ _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));
@@ -603,6 +666,9 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
tx_db_eeprom.load(*_mbc[mb].iface, USRP2_I2C_ADDR_TX_DB);
gdb_eeprom.load(*_mbc[mb].iface, USRP2_I2C_ADDR_TX_DB ^ 5);
+ //disable rx dc offset if LFRX
+ if (rx_db_eeprom.id == 0x000f) _tree->access<bool>(rx_fe_path / "dc_offset" / "enable").set(false);
+
//create the properties and register subscribers
_tree->create<dboard_eeprom_t>(mb_path / "dboards/A/rx_eeprom")
.set(rx_db_eeprom)
@@ -615,7 +681,7 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
.subscribe(boost::bind(&usrp2_impl::set_db_eeprom, this, mb, "gdb", _1));
//create a new dboard interface and manager
- _mbc[mb].dboard_iface = make_usrp2_dboard_iface(_mbc[mb].iface, _mbc[mb].clock);
+ _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,
@@ -657,10 +723,11 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){
_tree->access<std::string>(root / "time_source/value").set("none");
//GPS installed: use external ref, time, and init time spec
- if (_mbc[mb].gps.get() and _mbc[mb].gps->gps_detected()){
+ 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("external");
- _tree->access<std::string>(root / "clock_source/value").set("external");
+ _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)));
}
@@ -675,7 +742,7 @@ usrp2_impl::~usrp2_impl(void){UHD_SAFE_CALL(
)}
void usrp2_impl::set_mb_eeprom(const std::string &mb, const uhd::usrp::mboard_eeprom_t &mb_eeprom){
- mb_eeprom.commit(*(_mbc[mb].iface), mboard_eeprom_t::MAP_N100);
+ 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){
@@ -685,12 +752,12 @@ void usrp2_impl::set_db_eeprom(const std::string &mb, const std::string &type, c
}
sensor_value_t usrp2_impl::get_mimo_locked(const std::string &mb){
- const bool lock = (_mbc[mb].iface->peek32(U2_REG_IRQ_RB) & (1<<10)) != 0;
+ 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].iface->peek32(U2_REG_IRQ_RB) & (1<<11)) != 0;
+ const bool lock = (_mbc[mb].wbiface->peek32(U2_REG_IRQ_RB) & (1<<11)) != 0;
return sensor_value_t("Ref", lock, "locked", "unlocked");
}
@@ -729,14 +796,16 @@ meta_range_t usrp2_impl::get_tx_dsp_freq_range(const std::string &mb){
}
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);
+ 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
@@ -744,7 +813,7 @@ void usrp2_impl::update_clock_source(const std::string &mb, const std::string &s
case usrp2_iface::USRP2_REV3:
case usrp2_iface::USRP2_REV4:
- if (source == "internal") _mbc[mb].iface->poke32(U2_REG_MISC_CTRL_CLOCK, 0x10);
+ 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);
diff --git a/host/lib/usrp/usrp2/usrp2_impl.hpp b/host/lib/usrp/usrp2/usrp2_impl.hpp
index e5065c02d..a6c0d87cf 100644
--- a/host/lib/usrp/usrp2/usrp2_impl.hpp
+++ b/host/lib/usrp/usrp2/usrp2_impl.hpp
@@ -18,7 +18,9 @@
#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"
@@ -51,15 +53,13 @@ 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.
- * \param iface the usrp2 interface object
- * \param clk_ctrl the clock control object
- * \return a sptr to a new dboard interface
- */
+//! Make a usrp2 dboard interface.
uhd::usrp::dboard_iface::sptr make_usrp2_dboard_iface(
- usrp2_iface::sptr iface,
+ wb_iface::sptr wb_iface,
+ uhd::i2c_iface::sptr i2c_iface,
+ uhd::spi_iface::sptr spi_iface,
usrp2_clock_ctrl::sptr clk_ctrl
);
@@ -82,6 +82,9 @@ 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;
@@ -95,6 +98,7 @@ private:
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;
@@ -129,6 +133,7 @@ private:
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
index e14798ecb..7fe83e709 100644
--- a/host/lib/usrp/usrp2/usrp2_regs.hpp
+++ b/host/lib/usrp/usrp2/usrp2_regs.hpp
@@ -36,10 +36,10 @@
// Setting register offsets
////////////////////////////////////////////////////////////////////////
#define SR_MISC 0 // 7 regs
-#define SR_SIMTIMER 8 // 2
+#define SR_USER_REGS 8 // 2
#define SR_TIME64 10 // 6
#define SR_BUF_POOL 16 // 4
-#define SR_USER_REGS 20 // 2
+#define SR_SPI_CORE 20 // 3
#define SR_RX_FRONT 24 // 5
#define SR_RX_CTRL0 32 // 9
#define SR_RX_DSP0 48 // 7