aboutsummaryrefslogtreecommitdiffstats
path: root/host/lib/usrp/usrp1
diff options
context:
space:
mode:
Diffstat (limited to 'host/lib/usrp/usrp1')
-rw-r--r--host/lib/usrp/usrp1/CMakeLists.txt36
-rw-r--r--host/lib/usrp/usrp1/codec_ctrl.cpp419
-rw-r--r--host/lib/usrp/usrp1/codec_ctrl.hpp99
-rw-r--r--host/lib/usrp/usrp1/dboard_iface.cpp397
-rw-r--r--host/lib/usrp/usrp1/io_impl.cpp508
-rw-r--r--host/lib/usrp/usrp1/soft_time_ctrl.cpp228
-rw-r--r--host/lib/usrp/usrp1/soft_time_ctrl.hpp74
-rw-r--r--host/lib/usrp/usrp1/usrp1_calc_mux.hpp156
-rw-r--r--host/lib/usrp/usrp1/usrp1_iface.cpp205
-rw-r--r--host/lib/usrp/usrp1/usrp1_iface.hpp44
-rw-r--r--host/lib/usrp/usrp1/usrp1_impl.cpp444
-rw-r--r--host/lib/usrp/usrp1/usrp1_impl.hpp174
12 files changed, 2784 insertions, 0 deletions
diff --git a/host/lib/usrp/usrp1/CMakeLists.txt b/host/lib/usrp/usrp1/CMakeLists.txt
new file mode 100644
index 000000000..70bebe502
--- /dev/null
+++ b/host/lib/usrp/usrp1/CMakeLists.txt
@@ -0,0 +1,36 @@
+#
+# Copyright 2010-2011 Ettus Research LLC
+#
+# This program is free software: you can redistribute it and/or modify
+# it under the terms of the GNU General Public License as published by
+# the Free Software Foundation, either version 3 of the License, or
+# (at your option) any later version.
+#
+# This program is distributed in the hope that it will be useful,
+# but WITHOUT ANY WARRANTY; without even the implied warranty of
+# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+# GNU General Public License for more details.
+#
+# You should have received a copy of the GNU General Public License
+# along with this program. If not, see <http://www.gnu.org/licenses/>.
+#
+
+########################################################################
+# This file included, use CMake directory variables
+########################################################################
+
+########################################################################
+# Conditionally configure the USRP1 support
+########################################################################
+LIBUHD_REGISTER_COMPONENT("USRP1" ENABLE_USRP1 ON "ENABLE_LIBUHD;ENABLE_USB" OFF)
+
+IF(ENABLE_USRP1)
+ LIBUHD_APPEND_SOURCES(
+ ${CMAKE_CURRENT_SOURCE_DIR}/codec_ctrl.cpp
+ ${CMAKE_CURRENT_SOURCE_DIR}/dboard_iface.cpp
+ ${CMAKE_CURRENT_SOURCE_DIR}/io_impl.cpp
+ ${CMAKE_CURRENT_SOURCE_DIR}/soft_time_ctrl.cpp
+ ${CMAKE_CURRENT_SOURCE_DIR}/usrp1_iface.cpp
+ ${CMAKE_CURRENT_SOURCE_DIR}/usrp1_impl.cpp
+ )
+ENDIF(ENABLE_USRP1)
diff --git a/host/lib/usrp/usrp1/codec_ctrl.cpp b/host/lib/usrp/usrp1/codec_ctrl.cpp
new file mode 100644
index 000000000..c82569ea3
--- /dev/null
+++ b/host/lib/usrp/usrp1/codec_ctrl.cpp
@@ -0,0 +1,419 @@
+//
+// Copyright 2010-2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#include "codec_ctrl.hpp"
+#include "ad9862_regs.hpp"
+#include <uhd/utils/log.hpp>
+#include <uhd/utils/safe_call.hpp>
+#include <uhd/types/dict.hpp>
+#include <uhd/exception.hpp>
+#include <uhd/utils/algorithm.hpp>
+#include <uhd/utils/byteswap.hpp>
+#include <boost/cstdint.hpp>
+#include <boost/format.hpp>
+#include <boost/tuple/tuple.hpp>
+#include <boost/math/special_functions/round.hpp>
+#include <boost/assign/list_of.hpp>
+#include <iomanip>
+
+using namespace uhd;
+
+const gain_range_t usrp1_codec_ctrl::tx_pga_gain_range(-20, 0, double(0.1));
+const gain_range_t usrp1_codec_ctrl::rx_pga_gain_range(0, 20, 1);
+
+/***********************************************************************
+ * Codec Control Implementation
+ **********************************************************************/
+class usrp1_codec_ctrl_impl : public usrp1_codec_ctrl {
+public:
+ //structors
+ usrp1_codec_ctrl_impl(spi_iface::sptr iface, int spi_slave);
+ ~usrp1_codec_ctrl_impl(void);
+
+ //aux adc and dac control
+ double read_aux_adc(aux_adc_t which);
+ void write_aux_dac(aux_dac_t which, double volts);
+
+ //duc control
+ void set_duc_freq(double freq, double);
+ void enable_tx_digital(bool enb);
+
+ //pga gain control
+ void set_tx_pga_gain(double);
+ double get_tx_pga_gain(void);
+ void set_rx_pga_gain(double, char);
+ double get_rx_pga_gain(char);
+
+ //rx adc buffer control
+ void bypass_adc_buffers(bool bypass);
+
+private:
+ spi_iface::sptr _iface;
+ int _spi_slave;
+ ad9862_regs_t _ad9862_regs;
+ void send_reg(boost::uint8_t addr);
+ void recv_reg(boost::uint8_t addr);
+
+ double coarse_tune(double codec_rate, double freq);
+ double fine_tune(double codec_rate, double freq);
+};
+
+/***********************************************************************
+ * Codec Control Structors
+ **********************************************************************/
+usrp1_codec_ctrl_impl::usrp1_codec_ctrl_impl(spi_iface::sptr iface, int spi_slave){
+ _iface = iface;
+ _spi_slave = spi_slave;
+
+ //soft reset
+ _ad9862_regs.soft_reset = 1;
+ this->send_reg(0);
+
+ //initialize the codec register settings
+ _ad9862_regs.sdio_bidir = ad9862_regs_t::SDIO_BIDIR_SDIO_SDO;
+ _ad9862_regs.lsb_first = ad9862_regs_t::LSB_FIRST_MSB;
+ _ad9862_regs.soft_reset = 0;
+
+ //setup rx side of codec
+ _ad9862_regs.byp_buffer_a = 1;
+ _ad9862_regs.byp_buffer_b = 1;
+ _ad9862_regs.buffer_a_pd = 1;
+ _ad9862_regs.buffer_b_pd = 1;
+ _ad9862_regs.rx_pga_a = 0;
+ _ad9862_regs.rx_pga_b = 0;
+ _ad9862_regs.rx_twos_comp = 1;
+ _ad9862_regs.rx_hilbert = ad9862_regs_t::RX_HILBERT_DIS;
+
+ //setup tx side of codec
+ _ad9862_regs.two_data_paths = ad9862_regs_t::TWO_DATA_PATHS_BOTH;
+ _ad9862_regs.interleaved = ad9862_regs_t::INTERLEAVED_INTERLEAVED;
+ _ad9862_regs.tx_pga_gain = 199;
+ _ad9862_regs.tx_hilbert = ad9862_regs_t::TX_HILBERT_DIS;
+ _ad9862_regs.interp = ad9862_regs_t::INTERP_4;
+ _ad9862_regs.tx_twos_comp = 1;
+ _ad9862_regs.fine_mode = ad9862_regs_t::FINE_MODE_NCO;
+ _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_BYPASS;
+ _ad9862_regs.dac_a_coarse_gain = 0x3;
+ _ad9862_regs.dac_b_coarse_gain = 0x3;
+
+ //setup the dll
+ _ad9862_regs.input_clk_ctrl = ad9862_regs_t::INPUT_CLK_CTRL_EXTERNAL;
+ _ad9862_regs.dll_mult = ad9862_regs_t::DLL_MULT_2;
+ _ad9862_regs.dll_mode = ad9862_regs_t::DLL_MODE_FAST;
+
+ //setup clockout
+ _ad9862_regs.clkout2_div_factor = ad9862_regs_t::CLKOUT2_DIV_FACTOR_2;
+
+ //write the register settings to the codec
+ for (boost::uint8_t addr = 0; addr <= 25; addr++) {
+ this->send_reg(addr);
+ }
+
+ //always start conversions for aux ADC
+ _ad9862_regs.start_a = 1;
+ _ad9862_regs.start_b = 1;
+
+ //aux adc clock
+ _ad9862_regs.clk_4 = ad9862_regs_t::CLK_4_1_4;
+ this->send_reg(34);
+}
+
+usrp1_codec_ctrl_impl::~usrp1_codec_ctrl_impl(void){UHD_SAFE_CALL(
+ //set aux dacs to zero
+ this->write_aux_dac(AUX_DAC_A, 0);
+ this->write_aux_dac(AUX_DAC_B, 0);
+ this->write_aux_dac(AUX_DAC_C, 0);
+ this->write_aux_dac(AUX_DAC_D, 0);
+
+ //power down
+ _ad9862_regs.all_rx_pd = 1;
+ this->send_reg(1);
+ _ad9862_regs.tx_digital_pd = 1;
+ _ad9862_regs.tx_analog_pd = ad9862_regs_t::TX_ANALOG_PD_BOTH;
+ this->send_reg(8);
+)}
+
+/***********************************************************************
+ * Codec Control Gain Control Methods
+ **********************************************************************/
+static const int mtpgw = 255; //maximum tx pga gain word
+
+void usrp1_codec_ctrl_impl::set_tx_pga_gain(double gain){
+ int gain_word = int(mtpgw*(gain - tx_pga_gain_range.start())/(tx_pga_gain_range.stop() - tx_pga_gain_range.start()));
+ _ad9862_regs.tx_pga_gain = uhd::clip(gain_word, 0, mtpgw);
+ this->send_reg(16);
+}
+
+double usrp1_codec_ctrl_impl::get_tx_pga_gain(void){
+ return (_ad9862_regs.tx_pga_gain*(tx_pga_gain_range.stop() - tx_pga_gain_range.start())/mtpgw) + tx_pga_gain_range.start();
+}
+
+static const int mrpgw = 0x14; //maximum rx pga gain word
+
+void usrp1_codec_ctrl_impl::set_rx_pga_gain(double gain, char which){
+ int gain_word = int(mrpgw*(gain - rx_pga_gain_range.start())/(rx_pga_gain_range.stop() - rx_pga_gain_range.start()));
+ gain_word = uhd::clip(gain_word, 0, mrpgw);
+ switch(which){
+ case 'A':
+ _ad9862_regs.rx_pga_a = gain_word;
+ this->send_reg(2);
+ return;
+ case 'B':
+ _ad9862_regs.rx_pga_b = gain_word;
+ this->send_reg(3);
+ return;
+ default: UHD_THROW_INVALID_CODE_PATH();
+ }
+}
+
+double usrp1_codec_ctrl_impl::get_rx_pga_gain(char which){
+ int gain_word;
+ switch(which){
+ case 'A': gain_word = _ad9862_regs.rx_pga_a; break;
+ case 'B': gain_word = _ad9862_regs.rx_pga_b; break;
+ default: UHD_THROW_INVALID_CODE_PATH();
+ }
+ return (gain_word*(rx_pga_gain_range.stop() - rx_pga_gain_range.start())/mrpgw) + rx_pga_gain_range.start();
+}
+
+/***********************************************************************
+ * Codec Control AUX ADC Methods
+ **********************************************************************/
+static double aux_adc_to_volts(boost::uint8_t high, boost::uint8_t low)
+{
+ return double(((boost::uint16_t(high) << 2) | low)*3.3)/0x3ff;
+}
+
+double usrp1_codec_ctrl_impl::read_aux_adc(aux_adc_t which){
+ switch(which){
+ case AUX_ADC_A1:
+ _ad9862_regs.select_a = ad9862_regs_t::SELECT_A_AUX_ADC1;
+ this->send_reg(34); //start conversion and select mux
+ this->recv_reg(28); //read the value (2 bytes, 2 reads)
+ this->recv_reg(29);
+ return aux_adc_to_volts(_ad9862_regs.aux_adc_a1_9_2, _ad9862_regs.aux_adc_a1_1_0);
+
+ case AUX_ADC_A2:
+ _ad9862_regs.select_a = ad9862_regs_t::SELECT_A_AUX_ADC2;
+ this->send_reg(34); //start conversion and select mux
+ this->recv_reg(26); //read the value (2 bytes, 2 reads)
+ this->recv_reg(27);
+ return aux_adc_to_volts(_ad9862_regs.aux_adc_a2_9_2, _ad9862_regs.aux_adc_a2_1_0);
+
+ case AUX_ADC_B1:
+ _ad9862_regs.select_b = ad9862_regs_t::SELECT_B_AUX_ADC1;
+ this->send_reg(34); //start conversion and select mux
+ this->recv_reg(32); //read the value (2 bytes, 2 reads)
+ this->recv_reg(33);
+ return aux_adc_to_volts(_ad9862_regs.aux_adc_b1_9_2, _ad9862_regs.aux_adc_b1_1_0);
+
+ case AUX_ADC_B2:
+ _ad9862_regs.select_b = ad9862_regs_t::SELECT_B_AUX_ADC2;
+ this->send_reg(34); //start conversion and select mux
+ this->recv_reg(30); //read the value (2 bytes, 2 reads)
+ this->recv_reg(31);
+ return aux_adc_to_volts(_ad9862_regs.aux_adc_b2_9_2, _ad9862_regs.aux_adc_b2_1_0);
+ }
+ UHD_THROW_INVALID_CODE_PATH();
+}
+
+/***********************************************************************
+ * Codec Control AUX DAC Methods
+ **********************************************************************/
+void usrp1_codec_ctrl_impl::write_aux_dac(aux_dac_t which, double volts)
+{
+ //special case for aux dac d (aka sigma delta word)
+ if (which == AUX_DAC_D) {
+ boost::uint16_t dac_word = uhd::clip(boost::math::iround(volts*0xfff/3.3), 0, 0xfff);
+ _ad9862_regs.sig_delt_11_4 = boost::uint8_t(dac_word >> 4);
+ _ad9862_regs.sig_delt_3_0 = boost::uint8_t(dac_word & 0xf);
+ this->send_reg(42);
+ this->send_reg(43);
+ return;
+ }
+
+ //calculate the dac word for aux dac a, b, c
+ boost::uint8_t dac_word = uhd::clip(boost::math::iround(volts*0xff/3.3), 0, 0xff);
+
+ //setup a lookup table for the aux dac params (reg ref, reg addr)
+ typedef boost::tuple<boost::uint8_t*, boost::uint8_t> dac_params_t;
+ uhd::dict<aux_dac_t, dac_params_t> aux_dac_to_params = boost::assign::map_list_of
+ (AUX_DAC_A, dac_params_t(&_ad9862_regs.aux_dac_a, 36))
+ (AUX_DAC_B, dac_params_t(&_ad9862_regs.aux_dac_b, 37))
+ (AUX_DAC_C, dac_params_t(&_ad9862_regs.aux_dac_c, 38))
+ ;
+
+ //set the aux dac register
+ UHD_ASSERT_THROW(aux_dac_to_params.has_key(which));
+ boost::uint8_t *reg_ref, reg_addr;
+ boost::tie(reg_ref, reg_addr) = aux_dac_to_params[which];
+ *reg_ref = dac_word;
+ this->send_reg(reg_addr);
+}
+
+/***********************************************************************
+ * Codec Control SPI Methods
+ **********************************************************************/
+void usrp1_codec_ctrl_impl::send_reg(boost::uint8_t addr)
+{
+ boost::uint32_t reg = _ad9862_regs.get_write_reg(addr);
+
+ UHD_LOGV(often)
+ << "codec control write reg: 0x"
+ << std::setw(8) << std::hex << reg << std::endl
+ ;
+ _iface->write_spi(_spi_slave,
+ spi_config_t::EDGE_RISE, reg, 16);
+}
+
+void usrp1_codec_ctrl_impl::recv_reg(boost::uint8_t addr)
+{
+ boost::uint32_t reg = _ad9862_regs.get_read_reg(addr);
+
+ UHD_LOGV(often)
+ << "codec control read reg: 0x"
+ << std::setw(8) << std::hex << reg << std::endl
+ ;
+
+ boost::uint32_t ret = _iface->read_spi(_spi_slave,
+ spi_config_t::EDGE_RISE, reg, 16);
+
+ UHD_LOGV(often)
+ << "codec control read ret: 0x"
+ << std::setw(8) << std::hex << ret << std::endl
+ ;
+
+ _ad9862_regs.set_reg(addr, boost::uint16_t(ret));
+}
+
+/***********************************************************************
+ * DUC tuning
+ **********************************************************************/
+double usrp1_codec_ctrl_impl::coarse_tune(double codec_rate, double freq)
+{
+ double coarse_freq;
+
+ double coarse_freq_1 = codec_rate / 8;
+ double coarse_freq_2 = codec_rate / 4;
+ double coarse_limit_1 = coarse_freq_1 / 2;
+ double coarse_limit_2 = (coarse_freq_1 + coarse_freq_2) / 2;
+ double max_freq = coarse_freq_2 + .09375 * codec_rate;
+
+ if (freq < -max_freq) {
+ return false;
+ }
+ else if (freq < -coarse_limit_2) {
+ _ad9862_regs.neg_coarse_tune = ad9862_regs_t::NEG_COARSE_TUNE_NEG_SHIFT;
+ _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_FDAC_4;
+ coarse_freq = -coarse_freq_2;
+ }
+ else if (freq < -coarse_limit_1) {
+ _ad9862_regs.neg_coarse_tune = ad9862_regs_t::NEG_COARSE_TUNE_NEG_SHIFT;
+ _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_FDAC_8;
+ coarse_freq = -coarse_freq_1;
+ }
+ else if (freq < coarse_limit_1) {
+ _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_BYPASS;
+ coarse_freq = 0;
+ }
+ else if (freq < coarse_limit_2) {
+ _ad9862_regs.neg_coarse_tune = ad9862_regs_t::NEG_COARSE_TUNE_POS_SHIFT;
+ _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_FDAC_8;
+ coarse_freq = coarse_freq_1;
+ }
+ else if (freq <= max_freq) {
+ _ad9862_regs.neg_coarse_tune = ad9862_regs_t::NEG_COARSE_TUNE_POS_SHIFT;
+ _ad9862_regs.coarse_mod = ad9862_regs_t::COARSE_MOD_FDAC_4;
+ coarse_freq = coarse_freq_2;
+ }
+ else {
+ return 0;
+ }
+
+ return coarse_freq;
+}
+
+double usrp1_codec_ctrl_impl::fine_tune(double codec_rate, double target_freq)
+{
+ static const double scale_factor = std::pow(2.0, 24);
+
+ boost::uint32_t freq_word = boost::uint32_t(
+ boost::math::round(abs((target_freq / codec_rate) * scale_factor)));
+
+ double actual_freq = freq_word * codec_rate / scale_factor;
+
+ if (target_freq < 0) {
+ _ad9862_regs.neg_fine_tune = ad9862_regs_t::NEG_FINE_TUNE_NEG_SHIFT;
+ actual_freq = -actual_freq;
+ }
+ else {
+ _ad9862_regs.neg_fine_tune = ad9862_regs_t::NEG_FINE_TUNE_POS_SHIFT;
+ }
+
+ _ad9862_regs.fine_mode = ad9862_regs_t::FINE_MODE_NCO;
+ _ad9862_regs.ftw_23_16 = (freq_word >> 16) & 0xff;
+ _ad9862_regs.ftw_15_8 = (freq_word >> 8) & 0xff;
+ _ad9862_regs.ftw_7_0 = (freq_word >> 0) & 0xff;
+
+ return actual_freq;
+}
+
+void usrp1_codec_ctrl_impl::set_duc_freq(double freq, double rate)
+{
+ double codec_rate = rate * 2;
+ double coarse_freq = coarse_tune(codec_rate, freq);
+ double fine_freq = fine_tune(codec_rate / 4, freq - coarse_freq);
+
+ UHD_LOG
+ << "ad9862 tuning result:" << std::endl
+ << " requested: " << freq << std::endl
+ << " actual: " << coarse_freq + fine_freq << std::endl
+ << " coarse freq: " << coarse_freq << std::endl
+ << " fine freq: " << fine_freq << std::endl
+ << " codec rate: " << codec_rate << std::endl
+ ;
+
+ this->send_reg(20);
+ this->send_reg(21);
+ this->send_reg(22);
+ this->send_reg(23);
+}
+
+void usrp1_codec_ctrl_impl::enable_tx_digital(bool enb){
+ _ad9862_regs.tx_digital_pd = (enb)? 0 : 1;
+ this->send_reg(8);
+}
+
+/***********************************************************************
+ * Codec Control ADC buffer bypass
+ * Disable this for AC-coupled daughterboards (TVRX)
+ * By default it is initialized TRUE.
+ **********************************************************************/
+void usrp1_codec_ctrl_impl::bypass_adc_buffers(bool bypass) {
+ _ad9862_regs.byp_buffer_a = bypass;
+ _ad9862_regs.byp_buffer_b = bypass;
+ this->send_reg(2);
+}
+
+/***********************************************************************
+ * Codec Control Make
+ **********************************************************************/
+usrp1_codec_ctrl::sptr usrp1_codec_ctrl::make(spi_iface::sptr iface,
+ int spi_slave)
+{
+ return sptr(new usrp1_codec_ctrl_impl(iface, spi_slave));
+}
diff --git a/host/lib/usrp/usrp1/codec_ctrl.hpp b/host/lib/usrp/usrp1/codec_ctrl.hpp
new file mode 100644
index 000000000..70f4e0b61
--- /dev/null
+++ b/host/lib/usrp/usrp1/codec_ctrl.hpp
@@ -0,0 +1,99 @@
+//
+// Copyright 2010-2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#ifndef INCLUDED_USRP1_CODEC_CTRL_HPP
+#define INCLUDED_USRP1_CODEC_CTRL_HPP
+
+#include <uhd/types/serial.hpp>
+#include <uhd/types/ranges.hpp>
+#include <boost/shared_ptr.hpp>
+#include <boost/utility.hpp>
+
+/*!
+ * The usrp1 codec control:
+ * - Init/power down codec.
+ * - Read aux adc, write aux dac.
+ */
+class usrp1_codec_ctrl : boost::noncopyable{
+public:
+ typedef boost::shared_ptr<usrp1_codec_ctrl> sptr;
+
+ static const uhd::gain_range_t tx_pga_gain_range;
+ static const uhd::gain_range_t rx_pga_gain_range;
+
+ /*!
+ * Make a new clock control object.
+ * \param iface the spi iface object
+ * \param spi_slave which spi device
+ */
+ static sptr make(uhd::spi_iface::sptr iface, int spi_slave);
+
+ //! aux adc identifier constants
+ enum aux_adc_t{
+ AUX_ADC_A2 = 0xA2,
+ AUX_ADC_A1 = 0xA1,
+ AUX_ADC_B2 = 0xB2,
+ AUX_ADC_B1 = 0xB1
+ };
+
+ /*!
+ * Read an auxiliary adc:
+ * The internals remember which aux adc was read last.
+ * Therefore, the aux adc switch is only changed as needed.
+ * \param which which of the 4 adcs
+ * \return a value in volts
+ */
+ virtual double read_aux_adc(aux_adc_t which) = 0;
+
+ //! aux dac identifier constants
+ enum aux_dac_t{
+ AUX_DAC_A = 0xA,
+ AUX_DAC_B = 0xB,
+ AUX_DAC_C = 0xC,
+ AUX_DAC_D = 0xD
+ };
+
+ /*!
+ * Write an auxiliary dac.
+ * \param which which of the 4 dacs
+ * \param volts the level in in volts
+ */
+ virtual void write_aux_dac(aux_dac_t which, double volts) = 0;
+
+ //! Set the TX PGA gain
+ virtual void set_tx_pga_gain(double gain) = 0;
+
+ //! Get the TX PGA gain
+ virtual double get_tx_pga_gain(void) = 0;
+
+ //! Set the RX PGA gain ('A' or 'B')
+ virtual void set_rx_pga_gain(double gain, char which) = 0;
+
+ //! Get the RX PGA gain ('A' or 'B')
+ virtual double get_rx_pga_gain(char which) = 0;
+
+ //! Set the TX modulator frequency
+ virtual void set_duc_freq(double freq, double rate) = 0;
+
+ //! Enable or disable the digital part of the DAC
+ virtual void enable_tx_digital(bool enb) = 0;
+
+ //! Enable or disable ADC buffer bypass
+ virtual void bypass_adc_buffers(bool bypass) = 0;
+};
+
+#endif /* INCLUDED_USRP1_CODEC_CTRL_HPP */
diff --git a/host/lib/usrp/usrp1/dboard_iface.cpp b/host/lib/usrp/usrp1/dboard_iface.cpp
new file mode 100644
index 000000000..449ec64fe
--- /dev/null
+++ b/host/lib/usrp/usrp1/dboard_iface.cpp
@@ -0,0 +1,397 @@
+//
+// Copyright 2010-2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#include "usrp1_iface.hpp"
+#include "usrp1_impl.hpp"
+#include "fpga_regs_common.h"
+#include "usrp_spi_defs.h"
+#include "fpga_regs_standard.h"
+#include "codec_ctrl.hpp"
+#include <uhd/usrp/dboard_iface.hpp>
+#include <uhd/types/dict.hpp>
+#include <uhd/utils/assert_has.hpp>
+#include <boost/assign/list_of.hpp>
+#include <iostream>
+
+using namespace uhd;
+using namespace uhd::usrp;
+using namespace boost::assign;
+
+static const dboard_id_t tvrx_id(0x0040);
+
+class usrp1_dboard_iface : public dboard_iface {
+public:
+
+ usrp1_dboard_iface(usrp1_iface::sptr iface,
+ usrp1_codec_ctrl::sptr codec,
+ usrp1_impl::dboard_slot_t dboard_slot,
+ const double master_clock_rate,
+ const dboard_id_t &rx_dboard_id
+ ):
+ _dboard_slot(dboard_slot),
+ _master_clock_rate(master_clock_rate),
+ _rx_dboard_id(rx_dboard_id)
+ {
+ _iface = iface;
+ _codec = codec;
+
+ //init the clock rate shadows
+ this->set_clock_rate(UNIT_RX, this->get_clock_rates(UNIT_RX).front());
+ this->set_clock_rate(UNIT_TX, this->get_clock_rates(UNIT_TX).front());
+
+ //yes this is evil but it's necessary for TVRX to work on USRP1
+ if(_rx_dboard_id == tvrx_id) _codec->bypass_adc_buffers(false);
+ //else _codec->bypass_adc_buffers(false); //don't think this is necessary
+ }
+
+ ~usrp1_dboard_iface()
+ {
+ /* NOP */
+ }
+
+ special_props_t get_special_props()
+ {
+ special_props_t props;
+ props.soft_clock_divider = true;
+ props.mangle_i2c_addrs = (_dboard_slot == usrp1_impl::DBOARD_SLOT_B);
+ return props;
+ }
+
+ void write_aux_dac(unit_t, aux_dac_t, double);
+ double read_aux_adc(unit_t, aux_adc_t);
+
+ void _set_pin_ctrl(unit_t, boost::uint16_t);
+ void _set_atr_reg(unit_t, atr_reg_t, boost::uint16_t);
+ void _set_gpio_ddr(unit_t, boost::uint16_t);
+ void _set_gpio_out(unit_t, boost::uint16_t);
+ void set_gpio_debug(unit_t, int);
+ boost::uint16_t read_gpio(unit_t);
+
+ void write_i2c(boost::uint8_t, const byte_vector_t &);
+ byte_vector_t read_i2c(boost::uint8_t, size_t);
+
+ void write_spi(unit_t unit,
+ const spi_config_t &config,
+ boost::uint32_t data,
+ size_t num_bits);
+
+ boost::uint32_t read_write_spi(unit_t unit,
+ const spi_config_t &config,
+ boost::uint32_t data,
+ size_t num_bits);
+
+ void set_clock_rate(unit_t, double);
+ std::vector<double> get_clock_rates(unit_t);
+ double get_clock_rate(unit_t);
+ void set_clock_enabled(unit_t, bool);
+ double get_codec_rate(unit_t);
+
+private:
+ usrp1_iface::sptr _iface;
+ usrp1_codec_ctrl::sptr _codec;
+ uhd::dict<unit_t, double> _clock_rates;
+ const usrp1_impl::dboard_slot_t _dboard_slot;
+ const double _master_clock_rate;
+ const dboard_id_t _rx_dboard_id;
+};
+
+/***********************************************************************
+ * Make Function
+ **********************************************************************/
+dboard_iface::sptr usrp1_impl::make_dboard_iface(usrp1_iface::sptr iface,
+ usrp1_codec_ctrl::sptr codec,
+ usrp1_impl::dboard_slot_t dboard_slot,
+ const double master_clock_rate,
+ const dboard_id_t &rx_dboard_id
+){
+ return dboard_iface::sptr(new usrp1_dboard_iface(
+ iface, codec, dboard_slot, master_clock_rate, rx_dboard_id
+ ));
+}
+
+/***********************************************************************
+ * Clock Rates
+ **********************************************************************/
+static const dboard_id_t dbsrx_classic_id(0x0002);
+
+/*
+ * Daughterboard reference clock register
+ *
+ * Bit 7 - 1 turns on refclk, 0 allows IO use
+ * Bits 6:0 - Divider value
+ */
+void usrp1_dboard_iface::set_clock_rate(unit_t unit, double rate)
+{
+ assert_has(this->get_clock_rates(unit), rate, "dboard clock rate");
+ _clock_rates[unit] = rate;
+
+ if (unit == UNIT_RX && _rx_dboard_id == dbsrx_classic_id){
+ size_t divider = size_t(_master_clock_rate/rate);
+ switch(_dboard_slot){
+ case usrp1_impl::DBOARD_SLOT_A:
+ _iface->poke32(FR_RX_A_REFCLK, (divider & 0x7f) | 0x80);
+ break;
+
+ case usrp1_impl::DBOARD_SLOT_B:
+ _iface->poke32(FR_RX_B_REFCLK, (divider & 0x7f) | 0x80);
+ break;
+ }
+ }
+}
+
+std::vector<double> usrp1_dboard_iface::get_clock_rates(unit_t unit)
+{
+ std::vector<double> rates;
+ if (unit == UNIT_RX && _rx_dboard_id == dbsrx_classic_id){
+ for (size_t div = 1; div <= 127; div++)
+ rates.push_back(_master_clock_rate / div);
+ }
+ else{
+ rates.push_back(_master_clock_rate);
+ }
+ return rates;
+}
+
+double usrp1_dboard_iface::get_clock_rate(unit_t unit)
+{
+ return _clock_rates[unit];
+}
+
+void usrp1_dboard_iface::set_clock_enabled(unit_t, bool)
+{
+ //TODO we can only enable for special case anyway...
+}
+
+double usrp1_dboard_iface::get_codec_rate(unit_t){
+ return _master_clock_rate;
+}
+
+/***********************************************************************
+ * GPIO
+ **********************************************************************/
+void usrp1_dboard_iface::_set_pin_ctrl(unit_t unit, boost::uint16_t value)
+{
+ switch(unit) {
+ case UNIT_RX:
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ _iface->poke32(FR_ATR_MASK_1, value);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ _iface->poke32(FR_ATR_MASK_3, value);
+ break;
+ case UNIT_TX:
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ _iface->poke32(FR_ATR_MASK_0, value);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ _iface->poke32(FR_ATR_MASK_2, value);
+ break;
+ }
+}
+
+void usrp1_dboard_iface::_set_gpio_ddr(unit_t unit, boost::uint16_t value)
+{
+ switch(unit) {
+ case UNIT_RX:
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ _iface->poke32(FR_OE_1, 0xffff0000 | value);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ _iface->poke32(FR_OE_3, 0xffff0000 | value);
+ break;
+ case UNIT_TX:
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ _iface->poke32(FR_OE_0, 0xffff0000 | value);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ _iface->poke32(FR_OE_2, 0xffff0000 | value);
+ break;
+ }
+}
+
+void usrp1_dboard_iface::_set_gpio_out(unit_t unit, boost::uint16_t value)
+{
+ switch(unit) {
+ case UNIT_RX:
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ _iface->poke32(FR_IO_1, 0xffff0000 | value);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ _iface->poke32(FR_IO_3, 0xffff0000 | value);
+ break;
+ case UNIT_TX:
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ _iface->poke32(FR_IO_0, 0xffff0000 | value);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ _iface->poke32(FR_IO_2, 0xffff0000 | value);
+ break;
+ }
+}
+
+void usrp1_dboard_iface::set_gpio_debug(unit_t, int)
+{
+ /* NOP */
+}
+
+boost::uint16_t usrp1_dboard_iface::read_gpio(unit_t unit)
+{
+ boost::uint32_t out_value;
+
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ out_value = _iface->peek32(1);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ out_value = _iface->peek32(2);
+ else
+ UHD_THROW_INVALID_CODE_PATH();
+
+ switch(unit) {
+ case UNIT_RX:
+ return (boost::uint16_t)((out_value >> 16) & 0x0000ffff);
+ case UNIT_TX:
+ return (boost::uint16_t)((out_value >> 0) & 0x0000ffff);
+ }
+ UHD_ASSERT_THROW(false);
+}
+
+void usrp1_dboard_iface::_set_atr_reg(unit_t unit,
+ atr_reg_t atr, boost::uint16_t value)
+{
+ // Ignore unsupported states
+ if ((atr == ATR_REG_IDLE) || (atr == ATR_REG_TX_ONLY))
+ return;
+ if(atr == ATR_REG_RX_ONLY) {
+ switch(unit) {
+ case UNIT_RX:
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ _iface->poke32(FR_ATR_RXVAL_1, value);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ _iface->poke32(FR_ATR_RXVAL_3, value);
+ break;
+ case UNIT_TX:
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ _iface->poke32(FR_ATR_RXVAL_0, value);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ _iface->poke32(FR_ATR_RXVAL_2, value);
+ break;
+ }
+ } else if (atr == ATR_REG_FULL_DUPLEX) {
+ switch(unit) {
+ case UNIT_RX:
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ _iface->poke32(FR_ATR_TXVAL_1, value);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ _iface->poke32(FR_ATR_TXVAL_3, value);
+ break;
+ case UNIT_TX:
+ if (_dboard_slot == usrp1_impl::DBOARD_SLOT_A)
+ _iface->poke32(FR_ATR_TXVAL_0, value);
+ else if (_dboard_slot == usrp1_impl::DBOARD_SLOT_B)
+ _iface->poke32(FR_ATR_TXVAL_2, value);
+ break;
+ }
+ }
+}
+/***********************************************************************
+ * SPI
+ **********************************************************************/
+/*!
+ * Static function to convert a unit type to a spi slave device number.
+ * \param unit the dboard interface unit type enum
+ * \param slot the side (A or B) the dboard is attached
+ * \return the slave device number
+ */
+static boost::uint32_t unit_to_otw_spi_dev(dboard_iface::unit_t unit,
+ usrp1_impl::dboard_slot_t slot)
+{
+ switch(unit) {
+ case dboard_iface::UNIT_TX:
+ if (slot == usrp1_impl::DBOARD_SLOT_A)
+ return SPI_ENABLE_TX_A;
+ else if (slot == usrp1_impl::DBOARD_SLOT_B)
+ return SPI_ENABLE_TX_B;
+ else
+ break;
+ case dboard_iface::UNIT_RX:
+ if (slot == usrp1_impl::DBOARD_SLOT_A)
+ return SPI_ENABLE_RX_A;
+ else if (slot == usrp1_impl::DBOARD_SLOT_B)
+ return SPI_ENABLE_RX_B;
+ else
+ break;
+ }
+ UHD_THROW_INVALID_CODE_PATH();
+}
+
+void usrp1_dboard_iface::write_spi(unit_t unit,
+ const spi_config_t &config,
+ boost::uint32_t data,
+ size_t num_bits)
+{
+ _iface->write_spi(unit_to_otw_spi_dev(unit, _dboard_slot),
+ config, data, num_bits);
+}
+
+boost::uint32_t usrp1_dboard_iface::read_write_spi(unit_t unit,
+ const spi_config_t &config,
+ boost::uint32_t data,
+ size_t num_bits)
+{
+ return _iface->read_spi(unit_to_otw_spi_dev(unit, _dboard_slot),
+ config, data, num_bits);
+}
+
+/***********************************************************************
+ * I2C
+ **********************************************************************/
+void usrp1_dboard_iface::write_i2c(boost::uint8_t addr,
+ const byte_vector_t &bytes)
+{
+ return _iface->write_i2c(addr, bytes);
+}
+
+byte_vector_t usrp1_dboard_iface::read_i2c(boost::uint8_t addr,
+ size_t num_bytes)
+{
+ return _iface->read_i2c(addr, num_bytes);
+}
+
+/***********************************************************************
+ * Aux DAX/ADC
+ **********************************************************************/
+void usrp1_dboard_iface::write_aux_dac(dboard_iface::unit_t,
+ aux_dac_t which, double value)
+{
+ //same aux dacs for each unit
+ static const uhd::dict<aux_dac_t, usrp1_codec_ctrl::aux_dac_t>
+ which_to_aux_dac = map_list_of
+ (AUX_DAC_A, usrp1_codec_ctrl::AUX_DAC_A)
+ (AUX_DAC_B, usrp1_codec_ctrl::AUX_DAC_B)
+ (AUX_DAC_C, usrp1_codec_ctrl::AUX_DAC_C)
+ (AUX_DAC_D, usrp1_codec_ctrl::AUX_DAC_D);
+
+ _codec->write_aux_dac(which_to_aux_dac[which], value);
+}
+
+double usrp1_dboard_iface::read_aux_adc(dboard_iface::unit_t unit,
+ aux_adc_t which)
+{
+ static const
+ uhd::dict<unit_t, uhd::dict<aux_adc_t, usrp1_codec_ctrl::aux_adc_t> >
+ unit_to_which_to_aux_adc = map_list_of(UNIT_RX, map_list_of
+ (AUX_ADC_A, usrp1_codec_ctrl::AUX_ADC_A1)
+ (AUX_ADC_B, usrp1_codec_ctrl::AUX_ADC_B1))
+ (UNIT_TX, map_list_of
+ (AUX_ADC_A, usrp1_codec_ctrl::AUX_ADC_A2)
+ (AUX_ADC_B, usrp1_codec_ctrl::AUX_ADC_B2));
+
+ return _codec->read_aux_adc(unit_to_which_to_aux_adc[unit][which]);
+}
diff --git a/host/lib/usrp/usrp1/io_impl.cpp b/host/lib/usrp/usrp1/io_impl.cpp
new file mode 100644
index 000000000..e81b00d1c
--- /dev/null
+++ b/host/lib/usrp/usrp1/io_impl.cpp
@@ -0,0 +1,508 @@
+//
+// Copyright 2010-2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#include "validate_subdev_spec.hpp"
+#define SRPH_DONT_CHECK_SEQUENCE
+#include "../../transport/super_recv_packet_handler.hpp"
+#include "../../transport/super_send_packet_handler.hpp"
+#include "usrp1_calc_mux.hpp"
+#include "fpga_regs_standard.h"
+#include "usrp_commands.h"
+#include "usrp1_impl.hpp"
+#include <uhd/utils/msg.hpp>
+#include <uhd/utils/tasks.hpp>
+#include <uhd/utils/safe_call.hpp>
+#include <uhd/transport/bounded_buffer.hpp>
+#include <boost/math/special_functions/sign.hpp>
+#include <boost/math/special_functions/round.hpp>
+#include <boost/thread/thread.hpp>
+#include <boost/bind.hpp>
+#include <boost/format.hpp>
+
+using namespace uhd;
+using namespace uhd::usrp;
+using namespace uhd::transport;
+
+static const size_t alignment_padding = 512;
+
+/***********************************************************************
+ * Helper struct to associate an offset with a buffer
+ **********************************************************************/
+struct offset_send_buffer{
+ offset_send_buffer(void){
+ /* NOP */
+ }
+
+ offset_send_buffer(managed_send_buffer::sptr buff, size_t offset = 0):
+ buff(buff), offset(offset)
+ {
+ /* NOP */
+ }
+
+ //member variables
+ managed_send_buffer::sptr buff;
+ size_t offset; /* in bytes */
+};
+
+/***********************************************************************
+ * Reusable managed send buffer to handle aligned commits
+ **********************************************************************/
+class offset_managed_send_buffer : public managed_send_buffer{
+public:
+ typedef boost::function<void(offset_send_buffer&, offset_send_buffer&, size_t)> commit_cb_type;
+ offset_managed_send_buffer(const commit_cb_type &commit_cb):
+ _commit_cb(commit_cb)
+ {
+ /* NOP */
+ }
+
+ void commit(size_t size){
+ if (size != 0) this->_commit_cb(_curr_buff, _next_buff, size);
+ }
+
+ sptr get_new(
+ offset_send_buffer &curr_buff,
+ offset_send_buffer &next_buff
+ ){
+ _curr_buff = curr_buff;
+ _next_buff = next_buff;
+ return make_managed_buffer(this);
+ }
+
+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;
+};
+
+/***********************************************************************
+ * BS VRT packer/unpacker functions (since samples don't have headers)
+ **********************************************************************/
+static void usrp1_bs_vrt_packer(
+ boost::uint32_t *,
+ vrt::if_packet_info_t &if_packet_info
+){
+ if_packet_info.num_header_words32 = 0;
+ if_packet_info.num_packet_words32 = if_packet_info.num_payload_words32;
+}
+
+static void usrp1_bs_vrt_unpacker(
+ const boost::uint32_t *,
+ vrt::if_packet_info_t &if_packet_info
+){
+ if_packet_info.packet_type = vrt::if_packet_info_t::PACKET_TYPE_DATA;
+ if_packet_info.num_payload_words32 = if_packet_info.num_packet_words32;
+ if_packet_info.num_header_words32 = 0;
+ if_packet_info.packet_count = 0;
+ if_packet_info.sob = false;
+ if_packet_info.eob = false;
+ if_packet_info.has_sid = false;
+ if_packet_info.has_cid = false;
+ if_packet_info.has_tsi = false;
+ if_packet_info.has_tsf = false;
+ if_packet_info.has_tlr = false;
+}
+
+/***********************************************************************
+ * IO Implementation Details
+ **********************************************************************/
+struct usrp1_impl::io_impl{
+ io_impl(zero_copy_if::sptr data_transport):
+ data_transport(data_transport),
+ curr_buff(offset_send_buffer(data_transport->get_send_buff())),
+ omsb(boost::bind(&usrp1_impl::io_impl::commit_send_buff, this, _1, _2, _3))
+ {
+ /* NOP */
+ }
+
+ ~io_impl(void){
+ UHD_SAFE_CALL(flush_send_buff();)
+ }
+
+ zero_copy_if::sptr data_transport;
+
+ //state management for the vrt packet handler code
+ sph::recv_packet_handler recv_handler;
+ sph::send_packet_handler send_handler;
+
+ //wrapper around the actual send buffer interface
+ //all of this to ensure only aligned lengths are committed
+ //NOTE: you must commit before getting a new buffer
+ //since the vrt packet handler obeys this, we are ok
+ offset_send_buffer curr_buff;
+ offset_managed_send_buffer omsb;
+ void commit_send_buff(offset_send_buffer&, offset_send_buffer&, size_t);
+ void flush_send_buff(void);
+ managed_send_buffer::sptr get_send_buff(double timeout){
+ //try to get a new managed buffer with timeout
+ offset_send_buffer next_buff(data_transport->get_send_buff(timeout));
+ if (not next_buff.buff.get()) return managed_send_buffer::sptr(); /* propagate timeout here */
+
+ //make a new managed buffer with the offset buffs
+ return omsb.get_new(curr_buff, next_buff);
+ }
+
+ task::sptr vandal_task;
+ boost::system_time last_send_time;
+};
+
+/*!
+ * Perform an actual commit on the send buffer:
+ * Copy the remainder of alignment to the next buffer.
+ * Commit the current buffer at multiples of alignment.
+ */
+void usrp1_impl::io_impl::commit_send_buff(
+ offset_send_buffer &curr,
+ offset_send_buffer &next,
+ size_t num_bytes
+){
+ //total number of bytes now in the current buffer
+ size_t bytes_in_curr_buffer = curr.offset + num_bytes;
+
+ //calculate how many to commit and remainder
+ size_t num_bytes_remaining = bytes_in_curr_buffer % alignment_padding;
+ size_t num_bytes_to_commit = bytes_in_curr_buffer - num_bytes_remaining;
+
+ //copy the remainder into the next buffer
+ std::memcpy(
+ next.buff->cast<char *>() + next.offset,
+ curr.buff->cast<char *>() + num_bytes_to_commit,
+ num_bytes_remaining
+ );
+
+ //update the offset into the next buffer
+ next.offset += num_bytes_remaining;
+
+ //commit the current buffer
+ curr.buff->commit(num_bytes_to_commit);
+
+ //store the next buffer for the next call
+ curr_buff = next;
+}
+
+/*!
+ * Flush the current buffer by padding out to alignment and committing.
+ */
+void usrp1_impl::io_impl::flush_send_buff(void){
+ //calculate the number of bytes to alignment
+ size_t bytes_to_pad = (-1*curr_buff.offset)%alignment_padding;
+
+ //send at least alignment_padding to guarantee zeros are sent
+ if (bytes_to_pad == 0) bytes_to_pad = alignment_padding;
+
+ //get the buffer, clear, and commit (really current buffer)
+ managed_send_buffer::sptr buff = this->get_send_buff(.1);
+ if (buff.get() != NULL){
+ std::memset(buff->cast<void *>(), 0, bytes_to_pad);
+ buff->commit(bytes_to_pad);
+ }
+}
+
+/***********************************************************************
+ * Initialize internals within this file
+ **********************************************************************/
+void usrp1_impl::io_init(void){
+ _rx_otw_type.width = 16;
+ _rx_otw_type.shift = 0;
+ _rx_otw_type.byteorder = otw_type_t::BO_LITTLE_ENDIAN;
+
+ _tx_otw_type.width = 16;
+ _tx_otw_type.shift = 0;
+ _tx_otw_type.byteorder = otw_type_t::BO_LITTLE_ENDIAN;
+
+ _io_impl = UHD_PIMPL_MAKE(io_impl, (_data_transport));
+
+ //create a new vandal thread to poll xerflow conditions
+ _io_impl->vandal_task = task::make(boost::bind(
+ &usrp1_impl::vandal_conquest_loop, this
+ ));
+
+ //init some handler stuff
+ _io_impl->recv_handler.set_tick_rate(_master_clock_rate);
+ _io_impl->recv_handler.set_vrt_unpacker(&usrp1_bs_vrt_unpacker);
+ _io_impl->recv_handler.set_xport_chan_get_buff(0, boost::bind(
+ &uhd::transport::zero_copy_if::get_recv_buff, _io_impl->data_transport, _1
+ ));
+ _io_impl->send_handler.set_tick_rate(_master_clock_rate);
+ _io_impl->send_handler.set_vrt_packer(&usrp1_bs_vrt_packer);
+ _io_impl->send_handler.set_xport_chan_get_buff(0, boost::bind(
+ &usrp1_impl::io_impl::get_send_buff, _io_impl.get(), _1
+ ));
+
+ //init as disabled, then call the real function (uses restore)
+ this->enable_rx(false);
+ this->enable_tx(false);
+ rx_stream_on_off(false);
+ tx_stream_on_off(false);
+ _io_impl->flush_send_buff();
+}
+
+void usrp1_impl::rx_stream_on_off(bool enb){
+ this->restore_rx(enb);
+ //drain any junk in the receive transport after stop streaming command
+ while(not enb and _data_transport->get_recv_buff().get() != NULL){
+ /* NOP */
+ }
+}
+
+void usrp1_impl::tx_stream_on_off(bool enb){
+ _io_impl->last_send_time = boost::get_system_time();
+ if (_tx_enabled and not enb) _io_impl->flush_send_buff();
+ this->restore_tx(enb);
+}
+
+/*!
+ * Casually poll the overflow and underflow registers.
+ * On an underflow, push an async message into the queue and print.
+ * On an overflow, interleave an inline message into recv and print.
+ * This procedure creates "soft" inline and async user messages.
+ */
+void usrp1_impl::vandal_conquest_loop(void){
+
+ //initialize the async metadata
+ async_metadata_t async_metadata;
+ async_metadata.channel = 0;
+ async_metadata.has_time_spec = true;
+ async_metadata.event_code = async_metadata_t::EVENT_CODE_UNDERFLOW;
+
+ //initialize the inline metadata
+ rx_metadata_t inline_metadata;
+ inline_metadata.has_time_spec = true;
+ inline_metadata.error_code = rx_metadata_t::ERROR_CODE_OVERFLOW;
+
+ //start the polling loop...
+ try{ while (not boost::this_thread::interruption_requested()){
+ boost::uint8_t underflow = 0, overflow = 0;
+
+ //shutoff transmit if it has been too long since send() was called
+ if (_tx_enabled and (boost::get_system_time() - _io_impl->last_send_time) > boost::posix_time::milliseconds(100)){
+ this->tx_stream_on_off(false);
+ }
+
+ //always poll regardless of enabled so we can clear the conditions
+ _fx2_ctrl->usrp_control_read(
+ VRQ_GET_STATUS, 0, GS_TX_UNDERRUN, &underflow, sizeof(underflow)
+ );
+ _fx2_ctrl->usrp_control_read(
+ VRQ_GET_STATUS, 0, GS_RX_OVERRUN, &overflow, sizeof(overflow)
+ );
+
+ //handle message generation for xerflow conditions
+ if (_tx_enabled and underflow){
+ async_metadata.time_spec = _soft_time_ctrl->get_time();
+ _soft_time_ctrl->get_async_queue().push_with_pop_on_full(async_metadata);
+ UHD_MSG(fastpath) << "U";
+ }
+ if (_rx_enabled and overflow){
+ inline_metadata.time_spec = _soft_time_ctrl->get_time();
+ _soft_time_ctrl->get_inline_queue().push_with_pop_on_full(inline_metadata);
+ UHD_MSG(fastpath) << "O";
+ }
+
+ boost::this_thread::sleep(boost::posix_time::milliseconds(50));
+ }}
+ catch(const boost::thread_interrupted &){} //normal exit condition
+ catch(const std::exception &e){
+ UHD_MSG(error) << "The vandal caught an unexpected exception " << e.what() << std::endl;
+ }
+}
+
+/***********************************************************************
+ * Properties callback methods below
+ **********************************************************************/
+void usrp1_impl::update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){
+ boost::mutex::scoped_lock lock = _io_impl->recv_handler.get_scoped_lock();
+
+ //sanity checking
+ validate_subdev_spec(_tree, spec, "rx");
+
+ _rx_subdev_spec = spec; //shadow
+ _io_impl->recv_handler.resize(spec.size());
+ _io_impl->recv_handler.set_converter(_rx_otw_type, spec.size());
+
+ //set the mux and set the number of rx channels
+ std::vector<mapping_pair_t> mapping;
+ BOOST_FOREACH(const subdev_spec_pair_t &pair, spec){
+ const std::string conn = _tree->access<std::string>(str(boost::format(
+ "/mboards/0/dboards/%s/rx_frontends/%s/connection"
+ ) % pair.db_name % pair.sd_name)).get();
+ mapping.push_back(std::make_pair(pair.db_name, conn));
+ }
+ bool s = this->disable_rx();
+ _iface->poke32(FR_RX_MUX, calc_rx_mux(mapping));
+ this->restore_rx(s);
+}
+
+void usrp1_impl::update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){
+ boost::mutex::scoped_lock lock = _io_impl->send_handler.get_scoped_lock();
+
+ //sanity checking
+ validate_subdev_spec(_tree, spec, "tx");
+
+ _tx_subdev_spec = spec; //shadow
+ _io_impl->send_handler.resize(spec.size());
+ _io_impl->send_handler.set_converter(_tx_otw_type, spec.size());
+
+ //set the mux and set the number of tx channels
+ std::vector<mapping_pair_t> mapping;
+ BOOST_FOREACH(const subdev_spec_pair_t &pair, spec){
+ const std::string conn = _tree->access<std::string>(str(boost::format(
+ "/mboards/0/dboards/%s/tx_frontends/%s/connection"
+ ) % pair.db_name % pair.sd_name)).get();
+ mapping.push_back(std::make_pair(pair.db_name, conn));
+ }
+ bool s = this->disable_tx();
+ _iface->poke32(FR_TX_MUX, calc_tx_mux(mapping));
+ this->restore_tx(s);
+
+ //if the spec changes size, so does the max samples per packet...
+ _io_impl->send_handler.set_max_samples_per_packet(get_max_send_samps_per_packet());
+}
+
+double usrp1_impl::update_rx_samp_rate(const double samp_rate){
+ boost::mutex::scoped_lock lock = _io_impl->recv_handler.get_scoped_lock();
+
+ const size_t rate = uhd::clip<size_t>(
+ boost::math::iround(_master_clock_rate / samp_rate), size_t(std::ceil(_master_clock_rate / 8e6)), 256
+ );
+
+ bool s = this->disable_rx();
+ _iface->poke32(FR_DECIM_RATE, rate/2 - 1);
+ this->restore_rx(s);
+
+ _io_impl->recv_handler.set_samp_rate(_master_clock_rate / rate);
+ return _master_clock_rate / rate;
+}
+
+double usrp1_impl::update_tx_samp_rate(const double samp_rate){
+ boost::mutex::scoped_lock lock = _io_impl->send_handler.get_scoped_lock();
+
+ const size_t rate = uhd::clip<size_t>(
+ boost::math::iround(_master_clock_rate / samp_rate), size_t(std::ceil(_master_clock_rate / 8e6)), 256
+ );
+
+ bool s = this->disable_tx();
+ _iface->poke32(FR_INTERP_RATE, rate/2 - 1);
+ this->restore_tx(s);
+
+ _io_impl->send_handler.set_samp_rate(_master_clock_rate / rate);
+ return _master_clock_rate / rate;
+}
+
+double usrp1_impl::update_rx_dsp_freq(const size_t dspno, const double freq_){
+
+ //correct for outside of rate (wrap around)
+ double freq = std::fmod(freq_, _master_clock_rate);
+ if (std::abs(freq) > _master_clock_rate/2.0)
+ freq -= boost::math::sign(freq)*_master_clock_rate;
+
+ //calculate the freq register word (signed)
+ UHD_ASSERT_THROW(std::abs(freq) <= _master_clock_rate/2.0);
+ static const double scale_factor = std::pow(2.0, 32);
+ const boost::int32_t freq_word = boost::int32_t(boost::math::round((freq / _master_clock_rate) * scale_factor));
+
+ static const boost::uint32_t dsp_index_to_reg_val[4] = {
+ FR_RX_FREQ_0, FR_RX_FREQ_1, FR_RX_FREQ_2, FR_RX_FREQ_3
+ };
+ _iface->poke32(dsp_index_to_reg_val[dspno], ~freq_word + 1);
+
+ return (double(freq_word) / scale_factor) * _master_clock_rate;
+}
+
+double usrp1_impl::update_tx_dsp_freq(const size_t dspno, const double freq){
+ //map the freq shift key to a subdev spec to a particular codec chip
+ _dbc[_tx_subdev_spec.at(dspno).db_name].codec->set_duc_freq(freq, _master_clock_rate);
+ return freq; //assume infinite precision
+}
+
+/***********************************************************************
+ * Async Data
+ **********************************************************************/
+bool usrp1_impl::recv_async_msg(
+ async_metadata_t &async_metadata, double timeout
+){
+ boost::this_thread::disable_interruption di; //disable because the wait can throw
+ return _soft_time_ctrl->get_async_queue().pop_with_timed_wait(async_metadata, timeout);
+}
+
+/***********************************************************************
+ * Data send + helper functions
+ **********************************************************************/
+size_t usrp1_impl::get_max_send_samps_per_packet(void) const {
+ return (_data_transport->get_send_frame_size() - alignment_padding)
+ / _tx_otw_type.get_sample_size()
+ / _tx_subdev_spec.size()
+ ;
+}
+
+size_t usrp1_impl::send(
+ const send_buffs_type &buffs, size_t nsamps_per_buff,
+ const tx_metadata_t &metadata, const io_type_t &io_type,
+ send_mode_t send_mode, double timeout
+){
+ if (_soft_time_ctrl->send_pre(metadata, timeout)) return 0;
+
+ this->tx_stream_on_off(true); //always enable (it will do the right thing)
+ size_t num_samps_sent = _io_impl->send_handler.send(
+ buffs, nsamps_per_buff,
+ metadata, io_type,
+ send_mode, timeout
+ );
+
+ //handle eob flag (commit the buffer, /*disable the DACs*/)
+ //check num samps sent to avoid flush on incomplete/timeout
+ if (metadata.end_of_burst and num_samps_sent == nsamps_per_buff){
+ async_metadata_t metadata;
+ metadata.channel = 0;
+ metadata.has_time_spec = true;
+ metadata.time_spec = _soft_time_ctrl->get_time();
+ metadata.event_code = async_metadata_t::EVENT_CODE_BURST_ACK;
+ _soft_time_ctrl->get_async_queue().push_with_pop_on_full(metadata);
+ this->tx_stream_on_off(false);
+ }
+
+ return num_samps_sent;
+}
+
+/***********************************************************************
+ * Data recv + helper functions
+ **********************************************************************/
+size_t usrp1_impl::get_max_recv_samps_per_packet(void) const {
+ return _data_transport->get_recv_frame_size()
+ / _rx_otw_type.get_sample_size()
+ / _rx_subdev_spec.size()
+ ;
+}
+
+size_t usrp1_impl::recv(
+ const recv_buffs_type &buffs, size_t nsamps_per_buff,
+ rx_metadata_t &metadata, const io_type_t &io_type,
+ recv_mode_t recv_mode, double timeout
+){
+ //interleave a "soft" inline message into the receive stream:
+ if (_soft_time_ctrl->get_inline_queue().pop_with_haste(metadata)) return 0;
+
+ size_t num_samps_recvd = _io_impl->recv_handler.recv(
+ buffs, nsamps_per_buff,
+ metadata, io_type,
+ recv_mode, timeout
+ );
+
+ return _soft_time_ctrl->recv_post(metadata, num_samps_recvd);
+}
diff --git a/host/lib/usrp/usrp1/soft_time_ctrl.cpp b/host/lib/usrp/usrp1/soft_time_ctrl.cpp
new file mode 100644
index 000000000..78481c3ff
--- /dev/null
+++ b/host/lib/usrp/usrp1/soft_time_ctrl.cpp
@@ -0,0 +1,228 @@
+//
+// 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 "soft_time_ctrl.hpp"
+#include <uhd/utils/tasks.hpp>
+#include <boost/make_shared.hpp>
+#include <boost/thread/condition_variable.hpp>
+#include <boost/date_time/posix_time/posix_time.hpp>
+#include <iostream>
+
+using namespace uhd;
+using namespace uhd::usrp;
+using namespace uhd::transport;
+namespace pt = boost::posix_time;
+
+static const time_spec_t TWIDDLE(0.0011);
+
+/***********************************************************************
+ * Soft time control implementation
+ **********************************************************************/
+class soft_time_ctrl_impl : public soft_time_ctrl{
+public:
+
+ soft_time_ctrl_impl(const cb_fcn_type &stream_on_off):
+ _nsamps_remaining(0),
+ _stream_mode(stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS),
+ _cmd_queue(2),
+ _async_msg_queue(100),
+ _inline_msg_queue(100),
+ _stream_on_off(stream_on_off)
+ {
+ //synchronously spawn a new thread
+ _recv_cmd_task = task::make(boost::bind(&soft_time_ctrl_impl::recv_cmd_task, this));
+
+ //initialize the time to something
+ this->set_time(time_spec_t(0.0));
+ }
+
+ /*******************************************************************
+ * Time control
+ ******************************************************************/
+ void set_time(const time_spec_t &time){
+ boost::mutex::scoped_lock lock(_update_mutex);
+ _time_offset = time_spec_t::get_system_time() - time;
+ }
+
+ time_spec_t get_time(void){
+ boost::mutex::scoped_lock lock(_update_mutex);
+ return time_now();
+ }
+
+ UHD_INLINE time_spec_t time_now(void){
+ //internal get time without scoped lock
+ return time_spec_t::get_system_time() - _time_offset;
+ }
+
+ UHD_INLINE void sleep_until_time(
+ boost::mutex::scoped_lock &lock, const time_spec_t &time
+ ){
+ boost::condition_variable cond;
+ //use a condition variable to unlock, sleep, lock
+ double seconds_to_sleep = (time - time_now()).get_real_secs();
+ cond.timed_wait(lock, pt::microseconds(long(seconds_to_sleep*1e6)));
+ }
+
+ /*******************************************************************
+ * Receive control
+ ******************************************************************/
+ size_t recv_post(rx_metadata_t &md, const size_t nsamps){
+ boost::mutex::scoped_lock lock(_update_mutex);
+
+ //Since it timed out on the receive, check for inline messages...
+ //Must do a post check because recv() will not wake up for a message.
+ if (md.error_code == rx_metadata_t::ERROR_CODE_TIMEOUT){
+ if (_inline_msg_queue.pop_with_haste(md)) return 0;
+ }
+
+ //load the metadata with the expected time
+ md.has_time_spec = true;
+ md.time_spec = time_now();
+
+ //none of the stuff below matters in continuous streaming mode
+ if (_stream_mode == stream_cmd_t::STREAM_MODE_START_CONTINUOUS) return nsamps;
+
+ //When to stop streaming:
+ //The samples have been received and the stream mode is non-continuous.
+ //Rewrite the sample count to clip to the requested number of samples.
+ if (_nsamps_remaining <= nsamps) switch(_stream_mode){
+ case stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_MORE:{
+ rx_metadata_t metadata;
+ metadata.has_time_spec = true;
+ metadata.time_spec = this->time_now();
+ metadata.error_code = rx_metadata_t::ERROR_CODE_BROKEN_CHAIN;
+ _inline_msg_queue.push_with_pop_on_full(metadata);
+ } //continue to next case...
+ case stream_cmd_t::STREAM_MODE_NUM_SAMPS_AND_DONE:
+ md.end_of_burst = true;
+ this->issue_stream_cmd(stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS);
+ return _nsamps_remaining;
+ default: break;
+ }
+
+ //update the consumed samples
+ _nsamps_remaining -= nsamps;
+ return nsamps;
+ }
+
+ void issue_stream_cmd(const stream_cmd_t &cmd){
+ _cmd_queue.push_with_wait(boost::make_shared<stream_cmd_t>(cmd));
+ }
+
+ void stream_on_off(bool enb){
+ _stream_on_off(enb);
+ _nsamps_remaining = 0;
+ }
+
+ /*******************************************************************
+ * Transmit control
+ ******************************************************************/
+ bool send_pre(const tx_metadata_t &md, double &timeout){
+ if (not md.has_time_spec) return false;
+
+ boost::mutex::scoped_lock lock(_update_mutex);
+
+ time_spec_t time_at(md.time_spec - TWIDDLE);
+
+ //handle late packets
+ if (time_at < time_now()){
+ async_metadata_t metadata;
+ metadata.channel = 0;
+ metadata.has_time_spec = true;
+ metadata.time_spec = this->time_now();
+ metadata.event_code = async_metadata_t::EVENT_CODE_TIME_ERROR;
+ _async_msg_queue.push_with_pop_on_full(metadata);
+ return true;
+ }
+
+ timeout -= (time_at - time_now()).get_real_secs();
+ sleep_until_time(lock, time_at);
+ return false;
+ }
+
+ /*******************************************************************
+ * Thread control
+ ******************************************************************/
+ void recv_cmd_handle_cmd(const stream_cmd_t &cmd){
+ boost::mutex::scoped_lock lock(_update_mutex);
+
+ //handle the stream at time by sleeping
+ if (not cmd.stream_now){
+ time_spec_t time_at(cmd.time_spec - TWIDDLE);
+ if (time_at < time_now()){
+ rx_metadata_t metadata;
+ metadata.has_time_spec = true;
+ metadata.time_spec = this->time_now();
+ metadata.error_code = rx_metadata_t::ERROR_CODE_LATE_COMMAND;
+ _inline_msg_queue.push_with_pop_on_full(metadata);
+ this->issue_stream_cmd(stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS);
+ return;
+ }
+ else{
+ sleep_until_time(lock, time_at);
+ }
+ }
+
+ //When to stop streaming:
+ //Stop streaming when the command is a stop and streaming.
+ if (cmd.stream_mode == stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS
+ and _stream_mode != stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS
+ ) stream_on_off(false);
+
+ //When to start streaming:
+ //Start streaming when the command is not a stop and not streaming.
+ if (cmd.stream_mode != stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS
+ and _stream_mode == stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS
+ ) stream_on_off(true);
+
+ //update the state
+ _nsamps_remaining += cmd.num_samps;
+ _stream_mode = cmd.stream_mode;
+ }
+
+ void recv_cmd_task(void){ //task is looped
+ boost::shared_ptr<stream_cmd_t> cmd;
+ _cmd_queue.pop_with_wait(cmd);
+ recv_cmd_handle_cmd(*cmd);
+ }
+
+ bounded_buffer<async_metadata_t> &get_async_queue(void){
+ return _async_msg_queue;
+ }
+
+ bounded_buffer<rx_metadata_t> &get_inline_queue(void){
+ return _inline_msg_queue;
+ }
+
+private:
+ boost::mutex _update_mutex;
+ size_t _nsamps_remaining;
+ stream_cmd_t::stream_mode_t _stream_mode;
+ time_spec_t _time_offset;
+ bounded_buffer<boost::shared_ptr<stream_cmd_t> > _cmd_queue;
+ bounded_buffer<async_metadata_t> _async_msg_queue;
+ bounded_buffer<rx_metadata_t> _inline_msg_queue;
+ const cb_fcn_type _stream_on_off;
+ task::sptr _recv_cmd_task;
+};
+
+/***********************************************************************
+ * Soft time control factor
+ **********************************************************************/
+soft_time_ctrl::sptr soft_time_ctrl::make(const cb_fcn_type &stream_on_off){
+ return sptr(new soft_time_ctrl_impl(stream_on_off));
+}
diff --git a/host/lib/usrp/usrp1/soft_time_ctrl.hpp b/host/lib/usrp/usrp1/soft_time_ctrl.hpp
new file mode 100644
index 000000000..e91aaf6a2
--- /dev/null
+++ b/host/lib/usrp/usrp1/soft_time_ctrl.hpp
@@ -0,0 +1,74 @@
+//
+// Copyright 2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#ifndef INCLUDED_LIBUHD_USRP_USRP1_SOFT_TIME_CTRL_HPP
+#define INCLUDED_LIBUHD_USRP_USRP1_SOFT_TIME_CTRL_HPP
+
+#include <uhd/types/stream_cmd.hpp>
+#include <uhd/types/time_spec.hpp>
+#include <uhd/types/metadata.hpp>
+#include <uhd/transport/bounded_buffer.hpp>
+#include <boost/utility.hpp>
+#include <boost/shared_ptr.hpp>
+#include <boost/function.hpp>
+
+namespace uhd{ namespace usrp{
+
+/*!
+ * The soft time control emulates some of the
+ * advanced streaming capabilities of the later USRP models.
+ * Soft time control uses the system time to emulate
+ * timed transmits, timed receive commands, device time,
+ * and inline and async error messages.
+ */
+class soft_time_ctrl : boost::noncopyable{
+public:
+ typedef boost::shared_ptr<soft_time_ctrl> sptr;
+ typedef boost::function<void(bool)> cb_fcn_type;
+
+ /*!
+ * Make a new soft time control.
+ * \param stream_on_off a function to enable/disable rx
+ * \return a new soft time control object
+ */
+ static sptr make(const cb_fcn_type &stream_on_off);
+
+ //! Set the current time
+ virtual void set_time(const time_spec_t &time) = 0;
+
+ //! Get the current time
+ virtual time_spec_t get_time(void) = 0;
+
+ //! Call after the internal recv function
+ virtual size_t recv_post(rx_metadata_t &md, const size_t nsamps) = 0;
+
+ //! Call before the internal send function
+ virtual bool send_pre(const tx_metadata_t &md, double &timeout) = 0;
+
+ //! Issue a stream command to receive
+ virtual void issue_stream_cmd(const stream_cmd_t &cmd) = 0;
+
+ //! Get access to a buffer of async metadata
+ virtual transport::bounded_buffer<async_metadata_t> &get_async_queue(void) = 0;
+
+ //! Get access to a buffer of inline metadata
+ virtual transport::bounded_buffer<rx_metadata_t> &get_inline_queue(void) = 0;
+};
+
+}} //namespace
+
+#endif /* INCLUDED_LIBUHD_USRP_USRP1_SOFT_TIME_CTRL_HPP */
diff --git a/host/lib/usrp/usrp1/usrp1_calc_mux.hpp b/host/lib/usrp/usrp1/usrp1_calc_mux.hpp
new file mode 100644
index 000000000..31c190db0
--- /dev/null
+++ b/host/lib/usrp/usrp1/usrp1_calc_mux.hpp
@@ -0,0 +1,156 @@
+//
+// Copyright 2010-2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#include <uhd/config.hpp>
+#include <uhd/exception.hpp>
+#include <uhd/types/dict.hpp>
+#include <uhd/utils/algorithm.hpp>
+#include <boost/assign/list_of.hpp>
+#include <boost/format.hpp>
+#include <utility>
+#include <vector>
+#include <string>
+
+#ifndef INCLUDED_USRP1_CALC_MUX_HPP
+#define INCLUDED_USRP1_CALC_MUX_HPP
+
+//db_name, conn_type for the mux calculations below...
+typedef std::pair<std::string, std::string> mapping_pair_t;
+
+/***********************************************************************
+ * Calculate the RX mux value:
+ * The I and Q mux values are intentionally reversed to flip I and Q
+ * to account for the reversal in the type conversion routines.
+ **********************************************************************/
+static int calc_rx_mux_pair(int adc_for_i, int adc_for_q){
+ return (adc_for_i << 2) | (adc_for_q << 0); //shift reversal here
+}
+
+/*!
+ * 3 2 1 0
+ * 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0
+ * +-----------------------+-------+-------+-------+-------+-+-----+
+ * | must be zero | Q3| I3| Q2| I2| Q1| I1| Q0| I0|Z| NCH |
+ * +-----------------------+-------+-------+-------+-------+-+-----+
+ */
+static boost::uint32_t calc_rx_mux(const std::vector<mapping_pair_t> &mapping){
+ //create look-up-table for mapping dboard name and connection type to ADC flags
+ static const int ADC0 = 0, ADC1 = 1, ADC2 = 2, ADC3 = 3;
+ static const uhd::dict<std::string, uhd::dict<std::string, int> > name_to_conn_to_flag = boost::assign::map_list_of
+ ("A", boost::assign::map_list_of
+ ("IQ", calc_rx_mux_pair(ADC0, ADC1)) //I and Q
+ ("QI", calc_rx_mux_pair(ADC1, ADC0)) //I and Q
+ ("I", calc_rx_mux_pair(ADC0, ADC0)) //I and Q (Q identical but ignored Z=1)
+ ("Q", calc_rx_mux_pair(ADC1, ADC1)) //I and Q (Q identical but ignored Z=1)
+ )
+ ("B", boost::assign::map_list_of
+ ("IQ", calc_rx_mux_pair(ADC2, ADC3)) //I and Q
+ ("QI", calc_rx_mux_pair(ADC3, ADC2)) //I and Q
+ ("I", calc_rx_mux_pair(ADC2, ADC2)) //I and Q (Q identical but ignored Z=1)
+ ("Q", calc_rx_mux_pair(ADC3, ADC3)) //I and Q (Q identical but ignored Z=1)
+ )
+ ;
+
+ //extract the number of channels
+ const size_t nchan = mapping.size();
+
+ //calculate the channel flags
+ int channel_flags = 0;
+ size_t num_reals = 0, num_quads = 0;
+ BOOST_FOREACH(const mapping_pair_t &pair, uhd::reversed(mapping)){
+ const std::string name = pair.first, conn = pair.second;
+ if (conn == "IQ" or conn == "QI") num_quads++;
+ if (conn == "I" or conn == "Q") num_reals++;
+ channel_flags = (channel_flags << 4) | name_to_conn_to_flag[name][conn];
+ }
+
+ //calculate Z:
+ // for all real sources: Z = 1
+ // for all quadrature sources: Z = 0
+ // for mixed sources: warning + Z = 0
+ int Z = (num_quads > 0)? 0 : 1;
+ if (num_quads != 0 and num_reals != 0) UHD_MSG(warning) << boost::format(
+ "Mixing real and quadrature rx subdevices is not supported.\n"
+ "The Q input to the real source(s) will be non-zero.\n"
+ );
+
+ //calculate the rx mux value
+ return ((channel_flags & 0xffff) << 4) | ((Z & 0x1) << 3) | ((nchan & 0x7) << 0);
+}
+
+/***********************************************************************
+ * Calculate the TX mux value:
+ * The I and Q mux values are intentionally reversed to flip I and Q
+ * to account for the reversal in the type conversion routines.
+ **********************************************************************/
+static int calc_tx_mux_pair(int chn_for_i, int chn_for_q){
+ return (chn_for_i << 4) | (chn_for_q << 0); //shift reversal here
+}
+
+/*!
+ * 3 2 1 0
+ * 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0
+ * +-----------------------+-------+-------+-------+-------+-+-----+
+ * | | DAC1Q | DAC1I | DAC0Q | DAC0I |0| NCH |
+ * +-----------------------------------------------+-------+-+-----+
+ */
+static boost::uint32_t calc_tx_mux(const std::vector<mapping_pair_t> &mapping){
+ //create look-up-table for mapping channel number and connection type to flags
+ static const int ENB = 1 << 3, CHAN_I0 = 0, CHAN_Q0 = 1, CHAN_I1 = 2, CHAN_Q1 = 3;
+ static const uhd::dict<size_t, uhd::dict<std::string, int> > chan_to_conn_to_flag = boost::assign::map_list_of
+ (0, boost::assign::map_list_of
+ ("IQ", calc_tx_mux_pair(CHAN_I0 | ENB, CHAN_Q0 | ENB))
+ ("QI", calc_tx_mux_pair(CHAN_Q0 | ENB, CHAN_I0 | ENB))
+ ("I", calc_tx_mux_pair(CHAN_I0 | ENB, 0 ))
+ ("Q", calc_tx_mux_pair(0, CHAN_I0 | ENB))
+ )
+ (1, boost::assign::map_list_of
+ ("IQ", calc_tx_mux_pair(CHAN_I1 | ENB, CHAN_Q1 | ENB))
+ ("QI", calc_tx_mux_pair(CHAN_Q1 | ENB, CHAN_I1 | ENB))
+ ("I", calc_tx_mux_pair(CHAN_I1 | ENB, 0 ))
+ ("Q", calc_tx_mux_pair(0, CHAN_I1 | ENB))
+ )
+ ;
+
+ //extract the number of channels
+ size_t nchan = mapping.size();
+
+ //calculate the channel flags
+ int channel_flags = 0, chan = 0;
+ uhd::dict<std::string, int> slot_to_chan_count = boost::assign::map_list_of("A", 0)("B", 0);
+ BOOST_FOREACH(const mapping_pair_t &pair, mapping){
+ const std::string name = pair.first, conn = pair.second;
+
+ //combine the channel flags: shift for slot A vs B
+ if (name == "A") channel_flags |= chan_to_conn_to_flag[chan][conn] << 0;
+ if (name == "B") channel_flags |= chan_to_conn_to_flag[chan][conn] << 8;
+
+ //sanity check, only 1 channel per slot
+ slot_to_chan_count[name]++;
+ if (slot_to_chan_count[name] > 1) throw uhd::value_error(
+ "cannot assign dboard slot to multiple channels: " + name
+ );
+
+ //increment for the next channel
+ chan++;
+ }
+
+ //calculate the tx mux value
+ return ((channel_flags & 0xffff) << 4) | ((nchan & 0x7) << 0);
+}
+
+#endif /* INCLUDED_USRP1_CALC_MUX_HPP */
diff --git a/host/lib/usrp/usrp1/usrp1_iface.cpp b/host/lib/usrp/usrp1/usrp1_iface.cpp
new file mode 100644
index 000000000..c790aecb4
--- /dev/null
+++ b/host/lib/usrp/usrp1/usrp1_iface.cpp
@@ -0,0 +1,205 @@
+//
+// Copyright 2010-2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#include "usrp1_iface.hpp"
+#include "usrp_commands.h"
+#include <uhd/utils/log.hpp>
+#include <uhd/exception.hpp>
+#include <uhd/utils/byteswap.hpp>
+#include <boost/format.hpp>
+#include <stdexcept>
+#include <iomanip>
+
+using namespace uhd;
+using namespace uhd::usrp;
+using namespace uhd::transport;
+
+class usrp1_iface_impl : public usrp1_iface{
+public:
+ /*******************************************************************
+ * Structors
+ ******************************************************************/
+ usrp1_iface_impl(uhd::usrp::fx2_ctrl::sptr ctrl_transport)
+ {
+ _ctrl_transport = ctrl_transport;
+ }
+
+ ~usrp1_iface_impl(void)
+ {
+ /* NOP */
+ }
+
+ /*******************************************************************
+ * Peek and Poke
+ ******************************************************************/
+ void poke32(boost::uint32_t addr, boost::uint32_t value)
+ {
+ boost::uint32_t swapped = uhd::htonx(value);
+
+ UHD_LOGV(always)
+ << "poke32("
+ << std::dec << std::setw(2) << addr << ", 0x"
+ << std::hex << std::setw(8) << value << ")" << std::endl
+ ;
+
+ boost::uint8_t w_index_h = SPI_ENABLE_FPGA & 0xff;
+ boost::uint8_t w_index_l = (SPI_FMT_MSB | SPI_FMT_HDR_1) & 0xff;
+
+ int ret =_ctrl_transport->usrp_control_write(
+ VRQ_SPI_WRITE,
+ addr & 0x7f,
+ (w_index_h << 8) | (w_index_l << 0),
+ (unsigned char*) &swapped,
+ sizeof(boost::uint32_t));
+
+ if (ret < 0) throw uhd::io_error("USRP1: failed control write");
+ }
+
+ boost::uint32_t peek32(boost::uint32_t addr)
+ {
+ UHD_LOGV(always)
+ << "peek32("
+ << std::dec << std::setw(2) << addr << ")" << std::endl
+ ;
+
+ boost::uint32_t value_out;
+
+ boost::uint8_t w_index_h = SPI_ENABLE_FPGA & 0xff;
+ boost::uint8_t w_index_l = (SPI_FMT_MSB | SPI_FMT_HDR_1) & 0xff;
+
+ int ret = _ctrl_transport->usrp_control_read(
+ VRQ_SPI_READ,
+ 0x80 | (addr & 0x7f),
+ (w_index_h << 8) | (w_index_l << 0),
+ (unsigned char*) &value_out,
+ sizeof(boost::uint32_t));
+
+ if (ret < 0) throw uhd::io_error("USRP1: failed control read");
+
+ return uhd::ntohx(value_out);
+ }
+
+ void poke16(boost::uint32_t, boost::uint16_t) {
+ throw uhd::not_implemented_error("Unhandled command poke16()");
+ }
+
+ boost::uint16_t peek16(boost::uint32_t) {
+ throw uhd::not_implemented_error("Unhandled command peek16()");
+ return 0;
+ }
+
+ /*******************************************************************
+ * I2C
+ ******************************************************************/
+ void write_i2c(boost::uint8_t addr, const byte_vector_t &bytes){
+ return _ctrl_transport->write_i2c(addr, bytes);
+ }
+
+ byte_vector_t read_i2c(boost::uint8_t addr, size_t num_bytes){
+ return _ctrl_transport->read_i2c(addr, num_bytes);
+ }
+
+ /*******************************************************************
+ * SPI
+ *
+ * For non-readback transactions use the SPI_WRITE command, which is
+ * simpler and uses the USB control buffer for OUT data. No data
+ * needs to be returned.
+ *
+ * For readback transactions use SPI_TRANSACT, which places up to
+ * 4 bytes of OUT data in the device request fields and uses the
+ * control buffer for IN data.
+ ******************************************************************/
+ boost::uint32_t transact_spi(int which_slave,
+ const spi_config_t &,
+ boost::uint32_t bits,
+ size_t num_bits,
+ bool readback)
+ {
+ UHD_LOGV(always)
+ << "transact_spi: " << std::endl
+ << " slave: " << which_slave << std::endl
+ << " bits: " << bits << std::endl
+ << " num_bits: " << num_bits << std::endl
+ << " readback: " << readback << std::endl
+ ;
+ UHD_ASSERT_THROW((num_bits <= 32) && !(num_bits % 8));
+ size_t num_bytes = num_bits / 8;
+
+ if (readback) {
+ unsigned char buff[4] = {
+ (bits >> 0) & 0xff, (bits >> 8) & 0xff,
+ (bits >> 16) & 0xff, (bits >> 24) & 0xff
+ };
+ //conditions where there are two header bytes
+ if (num_bytes >= 3 and buff[num_bytes-1] != 0 and buff[num_bytes-2] != 0 and buff[num_bytes-3] == 0){
+ if (int(num_bytes-2) != _ctrl_transport->usrp_control_read(
+ VRQ_SPI_READ, (buff[num_bytes-1] << 8) | (buff[num_bytes-2] << 0),
+ (which_slave << 8) | SPI_FMT_MSB | SPI_FMT_HDR_2,
+ buff, num_bytes-2
+ )) throw uhd::io_error("USRP1: failed SPI readback transaction");
+ }
+
+ //conditions where there is one header byte
+ else if (num_bytes >= 2 and buff[num_bytes-1] != 0 and buff[num_bytes-2] == 0){
+ if (int(num_bytes-1) != _ctrl_transport->usrp_control_read(
+ VRQ_SPI_READ, buff[num_bytes-1],
+ (which_slave << 8) | SPI_FMT_MSB | SPI_FMT_HDR_1,
+ buff, num_bytes-1
+ )) throw uhd::io_error("USRP1: failed SPI readback transaction");
+ }
+ else{
+ throw uhd::io_error("USRP1: invalid input data for SPI readback");
+ }
+ boost::uint32_t val = (((boost::uint32_t)buff[0]) << 0) |
+ (((boost::uint32_t)buff[1]) << 8) |
+ (((boost::uint32_t)buff[2]) << 16) |
+ (((boost::uint32_t)buff[3]) << 24);
+ return val;
+ }
+ else {
+ // Byteswap on num_bytes
+ unsigned char buff[4] = { 0 };
+ for (size_t i = 1; i <= num_bytes; i++)
+ buff[num_bytes - i] = (bits >> ((i - 1) * 8)) & 0xff;
+
+ boost::uint8_t w_index_h = which_slave & 0xff;
+ boost::uint8_t w_index_l = (SPI_FMT_MSB | SPI_FMT_HDR_0) & 0xff;
+
+ int ret =_ctrl_transport->usrp_control_write(
+ VRQ_SPI_WRITE,
+ 0x00,
+ (w_index_h << 8) | (w_index_l << 0),
+ buff, num_bytes);
+
+ if (ret < 0) throw uhd::io_error("USRP1: failed SPI transaction");
+
+ return 0;
+ }
+ }
+
+private:
+ uhd::usrp::fx2_ctrl::sptr _ctrl_transport;
+};
+
+/***********************************************************************
+ * Public Make Function
+ **********************************************************************/
+usrp1_iface::sptr usrp1_iface::make(uhd::usrp::fx2_ctrl::sptr ctrl_transport)
+{
+ return sptr(new usrp1_iface_impl(ctrl_transport));
+}
diff --git a/host/lib/usrp/usrp1/usrp1_iface.hpp b/host/lib/usrp/usrp1/usrp1_iface.hpp
new file mode 100644
index 000000000..c1ac34f25
--- /dev/null
+++ b/host/lib/usrp/usrp1/usrp1_iface.hpp
@@ -0,0 +1,44 @@
+//
+// Copyright 2010-2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#ifndef INCLUDED_USRP1_IFACE_HPP
+#define INCLUDED_USRP1_IFACE_HPP
+
+#include "fx2_ctrl.hpp"
+#include "wb_iface.hpp"
+#include <uhd/types/serial.hpp>
+#include <boost/shared_ptr.hpp>
+#include <boost/utility.hpp>
+
+/*!
+ * The usrp1 interface class:
+ * Provides a set of functions to implementation layer.
+ * Including spi, peek, poke, control...
+ */
+class usrp1_iface : public wb_iface, public uhd::i2c_iface, public uhd::spi_iface, boost::noncopyable{
+public:
+ typedef boost::shared_ptr<usrp1_iface> sptr;
+
+ /*!
+ * Make a new usrp1 interface with the control transport.
+ * \param ctrl_transport the usrp controller object
+ * \return a new usrp1 interface object
+ */
+ static sptr make(uhd::usrp::fx2_ctrl::sptr ctrl_transport);
+};
+
+#endif /* INCLUDED_USRP1_IFACE_HPP */
diff --git a/host/lib/usrp/usrp1/usrp1_impl.cpp b/host/lib/usrp/usrp1/usrp1_impl.cpp
new file mode 100644
index 000000000..7a8f6497c
--- /dev/null
+++ b/host/lib/usrp/usrp1/usrp1_impl.cpp
@@ -0,0 +1,444 @@
+//
+// Copyright 2010-2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#include "usrp1_impl.hpp"
+#include "usrp_spi_defs.h"
+#include "usrp_commands.h"
+#include "fpga_regs_standard.h"
+#include "fpga_regs_common.h"
+#include "usrp_i2c_addr.h"
+#include <uhd/utils/log.hpp>
+#include <uhd/utils/safe_call.hpp>
+#include <uhd/transport/usb_control.hpp>
+#include <uhd/utils/msg.hpp>
+#include <uhd/exception.hpp>
+#include <uhd/utils/static.hpp>
+#include <uhd/utils/images.hpp>
+#include <boost/format.hpp>
+#include <boost/assign/list_of.hpp>
+#include <boost/filesystem.hpp>
+#include <boost/thread/thread.hpp>
+#include <boost/lexical_cast.hpp>
+
+using namespace uhd;
+using namespace uhd::usrp;
+using namespace uhd::transport;
+
+const boost::uint16_t USRP1_VENDOR_ID = 0xfffe;
+const boost::uint16_t USRP1_PRODUCT_ID = 0x0002;
+const boost::uint16_t FX2_VENDOR_ID = 0x04b4;
+const boost::uint16_t FX2_PRODUCT_ID = 0x8613;
+
+const std::vector<usrp1_impl::dboard_slot_t> usrp1_impl::_dboard_slots = boost::assign::list_of
+ (usrp1_impl::DBOARD_SLOT_A)(usrp1_impl::DBOARD_SLOT_B)
+;
+
+/***********************************************************************
+ * Discovery
+ **********************************************************************/
+static device_addrs_t usrp1_find(const device_addr_t &hint)
+{
+ device_addrs_t usrp1_addrs;
+
+ //return an empty list of addresses when type is set to non-usrp1
+ if (hint.has_key("type") and hint["type"] != "usrp1") return usrp1_addrs;
+
+ //Return an empty list of addresses when an address is specified,
+ //since an address is intended for a different, non-USB, device.
+ if (hint.has_key("addr")) return usrp1_addrs;
+
+ boost::uint16_t vid = hint.has_key("uninit") ? FX2_VENDOR_ID : USRP1_VENDOR_ID;
+ boost::uint16_t pid = hint.has_key("uninit") ? FX2_PRODUCT_ID : USRP1_PRODUCT_ID;
+
+ // Important note:
+ // The get device list calls are nested inside the for loop.
+ // This allows the usb guts to decontruct when not in use,
+ // so that re-enumeration after fw load can occur successfully.
+ // This requirement is a courtesy of libusb1.0 on windows.
+
+ //find the usrps and load firmware
+ BOOST_FOREACH(usb_device_handle::sptr handle, usb_device_handle::get_device_list(vid, pid)) {
+ //extract the firmware path for the USRP1
+ std::string usrp1_fw_image;
+ try{
+ usrp1_fw_image = find_image_path(hint.get("fw", "usrp1_fw.ihx"));
+ }
+ catch(...){
+ UHD_MSG(warning) << boost::format(
+ "Could not locate USRP1 firmware.\n"
+ "Please install the images package.\n"
+ );
+ return usrp1_addrs;
+ }
+ UHD_LOG << "USRP1 firmware image: " << usrp1_fw_image << std::endl;
+
+ usb_control::sptr control;
+ try{control = usb_control::make(handle);}
+ catch(const uhd::exception &){continue;} //ignore claimed
+
+ fx2_ctrl::make(control)->usrp_load_firmware(usrp1_fw_image);
+ }
+
+ //get descriptors again with serial number, but using the initialized VID/PID now since we have firmware
+ vid = USRP1_VENDOR_ID;
+ pid = USRP1_PRODUCT_ID;
+
+ BOOST_FOREACH(usb_device_handle::sptr handle, usb_device_handle::get_device_list(vid, pid)) {
+ usb_control::sptr control;
+ try{control = usb_control::make(handle);}
+ 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);
+ device_addr_t new_addr;
+ new_addr["type"] = "usrp1";
+ new_addr["name"] = mb_eeprom["name"];
+ new_addr["serial"] = handle->get_serial();
+ //this is a found usrp1 when the hint serial and name match or blank
+ if (
+ (not hint.has_key("name") or hint["name"] == new_addr["name"]) and
+ (not hint.has_key("serial") or hint["serial"] == new_addr["serial"])
+ ){
+ usrp1_addrs.push_back(new_addr);
+ }
+ }
+
+ return usrp1_addrs;
+}
+
+/***********************************************************************
+ * Make
+ **********************************************************************/
+static device::sptr usrp1_make(const device_addr_t &device_addr){
+ return device::sptr(new usrp1_impl(device_addr));
+}
+
+UHD_STATIC_BLOCK(register_usrp1_device){
+ device::register_device(&usrp1_find, &usrp1_make);
+}
+
+/***********************************************************************
+ * Structors
+ **********************************************************************/
+usrp1_impl::usrp1_impl(const device_addr_t &device_addr){
+ UHD_MSG(status) << "Opening a USRP1 device..." << std::endl;
+
+ //extract the FPGA path for the USRP1
+ std::string usrp1_fpga_image = find_image_path(
+ device_addr.get("fpga", "usrp1_fpga.rbf")
+ );
+ UHD_LOG << "USRP1 FPGA image: " << usrp1_fpga_image << std::endl;
+
+ //try to match the given device address with something on the USB bus
+ std::vector<usb_device_handle::sptr> device_list =
+ usb_device_handle::get_device_list(USRP1_VENDOR_ID, USRP1_PRODUCT_ID);
+
+ //locate the matching handle in the device list
+ usb_device_handle::sptr handle;
+ BOOST_FOREACH(usb_device_handle::sptr dev_handle, device_list) {
+ if (dev_handle->get_serial() == device_addr["serial"]){
+ handle = dev_handle;
+ break;
+ }
+ }
+ UHD_ASSERT_THROW(handle.get() != NULL); //better be found
+
+ ////////////////////////////////////////////////////////////////////
+ // Create controller objects
+ ////////////////////////////////////////////////////////////////////
+ //usb_control::sptr usb_ctrl = usb_control::make(handle);
+ _fx2_ctrl = fx2_ctrl::make(usb_control::make(handle));
+ _fx2_ctrl->usrp_load_fpga(usrp1_fpga_image);
+ _fx2_ctrl->usrp_init();
+ _data_transport = usb_zero_copy::make(
+ handle, // identifier
+ 6, // IN endpoint
+ 2, // OUT endpoint
+ device_addr // param hints
+ );
+ _iface = usrp1_iface::make(_fx2_ctrl);
+ _soft_time_ctrl = soft_time_ctrl::make(
+ boost::bind(&usrp1_impl::rx_stream_on_off, this, _1)
+ );
+ _dbc["A"]; _dbc["B"]; //ensure that keys exist
+
+ // Normal mode with no loopback or Rx counting
+ _iface->poke32(FR_MODE, 0x00000000);
+ _iface->poke32(FR_DEBUG_EN, 0x00000000);
+ _iface->poke32(FR_RX_SAMPLE_RATE_DIV, 0x00000001); //divide by 2
+ _iface->poke32(FR_TX_SAMPLE_RATE_DIV, 0x00000001); //divide by 2
+ _iface->poke32(FR_DC_OFFSET_CL_EN, 0x0000000f);
+
+ // Reset offset correction registers
+ _iface->poke32(FR_ADC_OFFSET_0, 0x00000000);
+ _iface->poke32(FR_ADC_OFFSET_1, 0x00000000);
+ _iface->poke32(FR_ADC_OFFSET_2, 0x00000000);
+ _iface->poke32(FR_ADC_OFFSET_3, 0x00000000);
+
+ // Set default for RX format to 16-bit I&Q and no half-band filter bypass
+ _iface->poke32(FR_RX_FORMAT, 0x00000300);
+
+ // Set default for TX format to 16-bit I&Q
+ _iface->poke32(FR_TX_FORMAT, 0x00000000);
+
+ UHD_LOG
+ << "USRP1 Capabilities" << std::endl
+ << " number of duc's: " << get_num_ddcs() << std::endl
+ << " number of ddc's: " << get_num_ducs() << std::endl
+ << " rx halfband: " << has_rx_halfband() << std::endl
+ << " tx halfband: " << has_tx_halfband() << std::endl
+ ;
+
+ ////////////////////////////////////////////////////////////////////
+ // Initialize the properties tree
+ ////////////////////////////////////////////////////////////////////
+ _tree = property_tree::make();
+ _tree->create<std::string>("/name").set("USRP1 Device");
+ const property_tree::path_type mb_path = "/mboards/0";
+ _tree->create<std::string>(mb_path / "name").set("USRP1 (Classic)");
+ _tree->create<std::string>(mb_path / "load_eeprom")
+ .subscribe(boost::bind(&fx2_ctrl::usrp_load_eeprom, _fx2_ctrl, _1));
+
+ ////////////////////////////////////////////////////////////////////
+ // setup the mboard eeprom
+ ////////////////////////////////////////////////////////////////////
+ const mboard_eeprom_t mb_eeprom(*_fx2_ctrl, mboard_eeprom_t::MAP_B000);
+ _tree->create<mboard_eeprom_t>(mb_path / "eeprom")
+ .set(mb_eeprom)
+ .subscribe(boost::bind(&usrp1_impl::set_mb_eeprom, this, _1));
+
+ ////////////////////////////////////////////////////////////////////
+ // create clock control objects
+ ////////////////////////////////////////////////////////////////////
+ _master_clock_rate = 64e6;
+ try{
+ if (not mb_eeprom["mcr"].empty())
+ _master_clock_rate = boost::lexical_cast<double>(mb_eeprom["mcr"]);
+ }catch(const std::exception &e){
+ UHD_MSG(error) << "Error parsing FPGA clock rate from EEPROM: " << e.what() << std::endl;
+ }
+ UHD_MSG(status) << boost::format("Using FPGA clock rate of %fMHz...") % (_master_clock_rate/1e6) << std::endl;
+ _tree->create<double>(mb_path / "tick_rate").set(_master_clock_rate);
+
+ ////////////////////////////////////////////////////////////////////
+ // create codec control objects
+ ////////////////////////////////////////////////////////////////////
+ BOOST_FOREACH(const std::string &db, _dbc.keys()){
+ _dbc[db].codec = usrp1_codec_ctrl::make(_iface, (db == "A")? SPI_ENABLE_CODEC_A : SPI_ENABLE_CODEC_B);
+ const property_tree::path_type rx_codec_path = mb_path / "rx_codecs" / db;
+ const property_tree::path_type tx_codec_path = mb_path / "tx_codecs" / db;
+ _tree->create<std::string>(rx_codec_path / "name").set("ad9522");
+ _tree->create<meta_range_t>(rx_codec_path / "gains/pga/range").set(usrp1_codec_ctrl::rx_pga_gain_range);
+ _tree->create<double>(rx_codec_path / "gains/pga/value")
+ .coerce(boost::bind(&usrp1_impl::update_rx_codec_gain, this, db, _1));
+ _tree->create<std::string>(tx_codec_path / "name").set("ad9522");
+ _tree->create<meta_range_t>(tx_codec_path / "gains/pga/range").set(usrp1_codec_ctrl::tx_pga_gain_range);
+ _tree->create<double>(tx_codec_path / "gains/pga/value")
+ .subscribe(boost::bind(&usrp1_codec_ctrl::set_tx_pga_gain, _dbc[db].codec, _1))
+ .publish(boost::bind(&usrp1_codec_ctrl::get_tx_pga_gain, _dbc[db].codec));
+ }
+
+ ////////////////////////////////////////////////////////////////////
+ // and do the misc mboard sensors
+ ////////////////////////////////////////////////////////////////////
+ //none for now...
+ _tree->create<int>(mb_path / "sensors"); //phony property so this dir exists
+
+ ////////////////////////////////////////////////////////////////////
+ // create frontend control objects
+ ////////////////////////////////////////////////////////////////////
+ _tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec")
+ .subscribe(boost::bind(&usrp1_impl::update_rx_subdev_spec, this, _1));
+ _tree->create<subdev_spec_t>(mb_path / "tx_subdev_spec")
+ .subscribe(boost::bind(&usrp1_impl::update_tx_subdev_spec, this, _1));
+
+ ////////////////////////////////////////////////////////////////////
+ // create rx dsp control objects
+ ////////////////////////////////////////////////////////////////////
+ for (size_t dspno = 0; dspno < get_num_ddcs(); dspno++){
+ property_tree::path_type rx_dsp_path = mb_path / str(boost::format("rx_dsps/%u") % dspno);
+ _tree->create<double>(rx_dsp_path / "rate/value")
+ .coerce(boost::bind(&usrp1_impl::update_rx_samp_rate, this, _1));
+ _tree->create<double>(rx_dsp_path / "freq/value")
+ .coerce(boost::bind(&usrp1_impl::update_rx_dsp_freq, this, dspno, _1));
+ _tree->create<meta_range_t>(rx_dsp_path / "freq/range")
+ .set(meta_range_t(-_master_clock_rate/2, +_master_clock_rate/2));
+ _tree->create<stream_cmd_t>(rx_dsp_path / "stream_cmd");
+ if (dspno == 0){
+ //only subscribe the callback for dspno 0 since it will stream all dsps
+ _tree->access<stream_cmd_t>(rx_dsp_path / "stream_cmd")
+ .subscribe(boost::bind(&soft_time_ctrl::issue_stream_cmd, _soft_time_ctrl, _1));
+ }
+ }
+
+ ////////////////////////////////////////////////////////////////////
+ // create tx dsp control objects
+ ////////////////////////////////////////////////////////////////////
+ for (size_t dspno = 0; dspno < get_num_ducs(); dspno++){
+ property_tree::path_type tx_dsp_path = mb_path / str(boost::format("tx_dsps/%u") % dspno);
+ _tree->create<double>(tx_dsp_path / "rate/value")
+ .coerce(boost::bind(&usrp1_impl::update_tx_samp_rate, this, _1));
+ _tree->create<double>(tx_dsp_path / "freq/value")
+ .coerce(boost::bind(&usrp1_impl::update_tx_dsp_freq, this, dspno, _1));
+ _tree->create<meta_range_t>(tx_dsp_path / "freq/range") //magic scalar comes from codec control:
+ .set(meta_range_t(-_master_clock_rate*0.6875, +_master_clock_rate*0.6875));
+ }
+
+ ////////////////////////////////////////////////////////////////////
+ // create time control objects
+ ////////////////////////////////////////////////////////////////////
+ _tree->create<time_spec_t>(mb_path / "time/now")
+ .publish(boost::bind(&soft_time_ctrl::get_time, _soft_time_ctrl))
+ .subscribe(boost::bind(&soft_time_ctrl::set_time, _soft_time_ctrl, _1));
+
+ _tree->create<std::vector<std::string> >(mb_path / "clock_source/options").set(std::vector<std::string>(1, "internal"));
+ _tree->create<std::vector<std::string> >(mb_path / "time_source/options").set(std::vector<std::string>(1, "none"));
+ _tree->create<std::string>(mb_path / "clock_source/value").set("internal");
+ _tree->create<std::string>(mb_path / "time_source/value").set("none");
+
+ ////////////////////////////////////////////////////////////////////
+ // create dboard control objects
+ ////////////////////////////////////////////////////////////////////
+ BOOST_FOREACH(const std::string &db, _dbc.keys()){
+
+ //read the dboard eeprom to extract the dboard ids
+ dboard_eeprom_t rx_db_eeprom, tx_db_eeprom, gdb_eeprom;
+ rx_db_eeprom.load(*_fx2_ctrl, (db == "A")? (I2C_ADDR_RX_A) : (I2C_ADDR_RX_B));
+ tx_db_eeprom.load(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A) : (I2C_ADDR_TX_B));
+ gdb_eeprom.load(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A ^ 5) : (I2C_ADDR_TX_B ^ 5));
+
+ //create the properties and register subscribers
+ _tree->create<dboard_eeprom_t>(mb_path / "dboards" / db/ "rx_eeprom")
+ .set(rx_db_eeprom)
+ .subscribe(boost::bind(&usrp1_impl::set_db_eeprom, this, db, "rx", _1));
+ _tree->create<dboard_eeprom_t>(mb_path / "dboards" / db/ "tx_eeprom")
+ .set(tx_db_eeprom)
+ .subscribe(boost::bind(&usrp1_impl::set_db_eeprom, this, db, "tx", _1));
+ _tree->create<dboard_eeprom_t>(mb_path / "dboards" / db/ "gdb_eeprom")
+ .set(gdb_eeprom)
+ .subscribe(boost::bind(&usrp1_impl::set_db_eeprom, this, db, "gdb", _1));
+
+ //create a new dboard interface and manager
+ _dbc[db].dboard_iface = make_dboard_iface(
+ _iface, _dbc[db].codec,
+ (db == "A")? DBOARD_SLOT_A : DBOARD_SLOT_B,
+ _master_clock_rate, rx_db_eeprom.id
+ );
+ _tree->create<dboard_iface::sptr>(mb_path / "dboards" / db/ "iface").set(_dbc[db].dboard_iface);
+ _dbc[db].dboard_manager = dboard_manager::make(
+ rx_db_eeprom.id,
+ ((gdb_eeprom.id == dboard_id_t::none())? tx_db_eeprom : gdb_eeprom).id,
+ _dbc[db].dboard_iface
+ );
+ BOOST_FOREACH(const std::string &name, _dbc[db].dboard_manager->get_rx_subdev_names()){
+ dboard_manager::populate_prop_tree_from_subdev(
+ _tree->subtree(mb_path / "dboards" / db/ "rx_frontends" / name),
+ _dbc[db].dboard_manager->get_rx_subdev(name)
+ );
+ }
+ BOOST_FOREACH(const std::string &name, _dbc[db].dboard_manager->get_tx_subdev_names()){
+ dboard_manager::populate_prop_tree_from_subdev(
+ _tree->subtree(mb_path / "dboards" / db/ "tx_frontends" / name),
+ _dbc[db].dboard_manager->get_tx_subdev(name)
+ );
+ }
+
+ //init the subdev specs if we have a dboard (wont leave this loop empty)
+ if (rx_db_eeprom.id != dboard_id_t::none() or _rx_subdev_spec.empty()){
+ _rx_subdev_spec = subdev_spec_t(db + ":" + _dbc[db].dboard_manager->get_rx_subdev_names()[0]);
+ }
+ if (tx_db_eeprom.id != dboard_id_t::none() or _tx_subdev_spec.empty()){
+ _tx_subdev_spec = subdev_spec_t(db + ":" + _dbc[db].dboard_manager->get_tx_subdev_names()[0]);
+ }
+ }
+
+ //initialize io handling
+ this->io_init();
+
+ ////////////////////////////////////////////////////////////////////
+ // do some post-init tasks
+ ////////////////////////////////////////////////////////////////////
+ //and now that the tick rate is set, init the host rates to something
+ BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){
+ _tree->access<double>(mb_path / "rx_dsps" / name / "rate" / "value").set(1e6);
+ }
+ BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){
+ _tree->access<double>(mb_path / "tx_dsps" / name / "rate" / "value").set(1e6);
+ }
+
+ _tree->access<subdev_spec_t>(mb_path / "rx_subdev_spec").set(_rx_subdev_spec);
+ _tree->access<subdev_spec_t>(mb_path / "tx_subdev_spec").set(_tx_subdev_spec);
+
+}
+
+usrp1_impl::~usrp1_impl(void){
+ _io_impl.reset(); //stops vandal before other stuff gets deconstructed
+ UHD_SAFE_CALL(
+ this->enable_rx(false);
+ this->enable_tx(false);
+ )
+}
+
+/*!
+ * Capabilities Register
+ *
+ * 3 2 1 0
+ * 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0
+ * +-----------------------------------------------+-+-----+-+-----+
+ * | Reserved |T|DUCs |R|DDCs |
+ * +-----------------------------------------------+-+-----+-+-----+
+ */
+size_t usrp1_impl::get_num_ddcs(void){
+ boost::uint32_t regval = _iface->peek32(FR_RB_CAPS);
+ return (regval >> 0) & 0x0007;
+}
+
+size_t usrp1_impl::get_num_ducs(void){
+ boost::uint32_t regval = _iface->peek32(FR_RB_CAPS);
+ return (regval >> 4) & 0x0007;
+}
+
+bool usrp1_impl::has_rx_halfband(void){
+ boost::uint32_t regval = _iface->peek32(FR_RB_CAPS);
+ return (regval >> 3) & 0x0001;
+}
+
+bool usrp1_impl::has_tx_halfband(void){
+ boost::uint32_t regval = _iface->peek32(FR_RB_CAPS);
+ return (regval >> 7) & 0x0001;
+}
+
+/***********************************************************************
+ * Properties callback methods below
+ **********************************************************************/
+void usrp1_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){
+ mb_eeprom.commit(*_fx2_ctrl, mboard_eeprom_t::MAP_B000);
+}
+
+void usrp1_impl::set_db_eeprom(const std::string &db, const std::string &type, const uhd::usrp::dboard_eeprom_t &db_eeprom){
+ if (type == "rx") db_eeprom.store(*_fx2_ctrl, (db == "A")? (I2C_ADDR_RX_A) : (I2C_ADDR_RX_B));
+ if (type == "tx") db_eeprom.store(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A) : (I2C_ADDR_TX_B));
+ if (type == "gdb") db_eeprom.store(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A ^ 5) : (I2C_ADDR_TX_B ^ 5));
+}
+
+double usrp1_impl::update_rx_codec_gain(const std::string &db, const double gain){
+ //set gain on both I and Q, readback on one
+ //TODO in the future, gains should have individual control
+ _dbc[db].codec->set_rx_pga_gain(gain, 'A');
+ _dbc[db].codec->set_rx_pga_gain(gain, 'B');
+ return _dbc[db].codec->get_rx_pga_gain('A');
+}
diff --git a/host/lib/usrp/usrp1/usrp1_impl.hpp b/host/lib/usrp/usrp1/usrp1_impl.hpp
new file mode 100644
index 000000000..1fe0c1784
--- /dev/null
+++ b/host/lib/usrp/usrp1/usrp1_impl.hpp
@@ -0,0 +1,174 @@
+//
+// Copyright 2010-2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#include "usrp1_iface.hpp"
+#include "codec_ctrl.hpp"
+#include "soft_time_ctrl.hpp"
+#include <uhd/device.hpp>
+#include <uhd/property_tree.hpp>
+#include <uhd/utils/pimpl.hpp>
+#include <uhd/types/dict.hpp>
+#include <uhd/types/otw_type.hpp>
+#include <uhd/types/clock_config.hpp>
+#include <uhd/types/stream_cmd.hpp>
+#include <uhd/usrp/dboard_id.hpp>
+#include <uhd/usrp/mboard_eeprom.hpp>
+#include <uhd/usrp/subdev_spec.hpp>
+#include <uhd/usrp/dboard_eeprom.hpp>
+#include <uhd/usrp/dboard_manager.hpp>
+#include <uhd/transport/usb_zero_copy.hpp>
+
+#ifndef INCLUDED_USRP1_IMPL_HPP
+#define INCLUDED_USRP1_IMPL_HPP
+
+/*!
+ * USRP1 implementation guts:
+ * The implementation details are encapsulated here.
+ * Handles properties on the mboard, dboard, dsps...
+ */
+class usrp1_impl : public uhd::device {
+public:
+ //! used everywhere to differentiate slots/sides...
+ enum dboard_slot_t{
+ DBOARD_SLOT_A = 'A',
+ DBOARD_SLOT_B = 'B'
+ };
+ //and a way to enumerate through a list of the above...
+ static const std::vector<dboard_slot_t> _dboard_slots;
+
+ //structors
+ usrp1_impl(const uhd::device_addr_t &);
+ ~usrp1_impl(void);
+
+ //the io interface
+ size_t send(const send_buffs_type &,
+ size_t,
+ const uhd::tx_metadata_t &,
+ const uhd::io_type_t &,
+ send_mode_t, double);
+
+ size_t recv(const recv_buffs_type &,
+ size_t, uhd::rx_metadata_t &,
+ const uhd::io_type_t &,
+ recv_mode_t, double);
+
+ size_t get_max_send_samps_per_packet(void) const;
+
+ size_t get_max_recv_samps_per_packet(void) const;
+
+ bool recv_async_msg(uhd::async_metadata_t &, double);
+
+private:
+ uhd::property_tree::sptr _tree;
+
+ //device properties interface
+ void get(const wax::obj &, wax::obj &val){
+ val = _tree; //entry point into property tree
+ }
+
+ //controllers
+ uhd::usrp::fx2_ctrl::sptr _fx2_ctrl;
+ usrp1_iface::sptr _iface;
+ uhd::usrp::soft_time_ctrl::sptr _soft_time_ctrl;
+ uhd::transport::usb_zero_copy::sptr _data_transport;
+ struct db_container_type{
+ usrp1_codec_ctrl::sptr codec;
+ uhd::usrp::dboard_iface::sptr dboard_iface;
+ uhd::usrp::dboard_manager::sptr dboard_manager;
+ };
+ uhd::dict<std::string, db_container_type> _dbc;
+
+ double _master_clock_rate; //clock rate shadow
+
+ void set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &);
+ void set_db_eeprom(const std::string &, const std::string &, const uhd::usrp::dboard_eeprom_t &);
+ double update_rx_codec_gain(const std::string &, const double); //sets A and B at once
+ void update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &);
+ void update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &);
+ double update_rx_samp_rate(const double);
+ double update_tx_samp_rate(const double);
+ double update_rx_dsp_freq(const size_t, const double);
+ double update_tx_dsp_freq(const size_t, const double);
+
+ static uhd::usrp::dboard_iface::sptr make_dboard_iface(
+ usrp1_iface::sptr,
+ usrp1_codec_ctrl::sptr,
+ dboard_slot_t,
+ const double,
+ const uhd::usrp::dboard_id_t &
+ );
+
+ //handle io stuff
+ UHD_PIMPL_DECL(io_impl) _io_impl;
+ void io_init(void);
+ void rx_stream_on_off(bool);
+ void tx_stream_on_off(bool);
+ void handle_overrun(size_t);
+
+ //otw types
+ uhd::otw_type_t _rx_otw_type, _tx_otw_type;
+ uhd::usrp::subdev_spec_t _rx_subdev_spec, _tx_subdev_spec;
+
+ //capabilities
+ size_t get_num_ducs(void);
+ size_t get_num_ddcs(void);
+ bool has_rx_halfband(void);
+ bool has_tx_halfband(void);
+
+ void vandal_conquest_loop(void);
+
+ //handle the enables
+ bool _rx_enabled, _tx_enabled;
+ void enable_rx(bool enb){
+ _rx_enabled = enb;
+ _fx2_ctrl->usrp_rx_enable(enb);
+ }
+ void enable_tx(bool enb){
+ _tx_enabled = enb;
+ _fx2_ctrl->usrp_tx_enable(enb);
+ }
+
+ //conditionally disable and enable rx
+ bool disable_rx(void){
+ if (_rx_enabled){
+ enable_rx(false);
+ return true;
+ }
+ return false;
+ }
+ void restore_rx(bool last){
+ if (last != _rx_enabled){
+ enable_rx(last);
+ }
+ }
+
+ //conditionally disable and enable tx
+ bool disable_tx(void){
+ if (_tx_enabled){
+ enable_tx(false);
+ return true;
+ }
+ return false;
+ }
+ void restore_tx(bool last){
+ if (last != _tx_enabled){
+ enable_tx(last);
+ }
+ }
+};
+
+#endif /* INCLUDED_USRP1_IMPL_HPP */