summaryrefslogtreecommitdiffstats
path: root/host/lib
diff options
context:
space:
mode:
authorJosh Blum <josh@joshknows.com>2011-07-01 11:33:03 -0700
committerJosh Blum <josh@joshknows.com>2011-07-01 11:33:03 -0700
commit7613f8ce367ed0d80d2b717821583991d3aa509a (patch)
treed94067c9cde586968b561e6732b5590f921bdf93 /host/lib
parent54e58dd0755b0fd7577e3f31df24401f96f33a9b (diff)
downloaduhd-7613f8ce367ed0d80d2b717821583991d3aa509a.tar.gz
uhd-7613f8ce367ed0d80d2b717821583991d3aa509a.tar.bz2
uhd-7613f8ce367ed0d80d2b717821583991d3aa509a.zip
usrp1: implemented properties interface on usrp1
Diffstat (limited to 'host/lib')
-rw-r--r--host/lib/usrp/CMakeLists.txt2
-rw-r--r--host/lib/usrp/usrp1/CMakeLists.txt9
-rw-r--r--host/lib/usrp/usrp1/codec_ctrl.cpp24
-rw-r--r--host/lib/usrp/usrp1/codec_ctrl.hpp12
-rw-r--r--host/lib/usrp/usrp1/dboard_iface.cpp23
-rw-r--r--host/lib/usrp/usrp1/io_impl.cpp173
-rw-r--r--host/lib/usrp/usrp1/usrp1_calc_mux.hpp156
-rw-r--r--host/lib/usrp/usrp1/usrp1_iface.cpp102
-rw-r--r--host/lib/usrp/usrp1/usrp1_iface.hpp22
-rw-r--r--host/lib/usrp/usrp1/usrp1_impl.cpp354
-rw-r--r--host/lib/usrp/usrp1/usrp1_impl.hpp159
11 files changed, 634 insertions, 402 deletions
diff --git a/host/lib/usrp/CMakeLists.txt b/host/lib/usrp/CMakeLists.txt
index e29367e67..77b13cb15 100644
--- a/host/lib/usrp/CMakeLists.txt
+++ b/host/lib/usrp/CMakeLists.txt
@@ -33,7 +33,7 @@ LIBUHD_APPEND_SOURCES(
INCLUDE_SUBDIRECTORY(cores)
INCLUDE_SUBDIRECTORY(dboard)
INCLUDE_SUBDIRECTORY(fx2)
-#INCLUDE_SUBDIRECTORY(usrp1)
+INCLUDE_SUBDIRECTORY(usrp1)
INCLUDE_SUBDIRECTORY(usrp2)
INCLUDE_SUBDIRECTORY(b100)
INCLUDE_SUBDIRECTORY(e100)
diff --git a/host/lib/usrp/usrp1/CMakeLists.txt b/host/lib/usrp/usrp1/CMakeLists.txt
index c208cfe8c..70bebe502 100644
--- a/host/lib/usrp/usrp1/CMakeLists.txt
+++ b/host/lib/usrp/usrp1/CMakeLists.txt
@@ -26,20 +26,11 @@ LIBUHD_REGISTER_COMPONENT("USRP1" ENABLE_USRP1 ON "ENABLE_LIBUHD;ENABLE_USB" OFF
IF(ENABLE_USRP1)
LIBUHD_APPEND_SOURCES(
- ${CMAKE_CURRENT_SOURCE_DIR}/clock_ctrl.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/clock_ctrl.hpp
${CMAKE_CURRENT_SOURCE_DIR}/codec_ctrl.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/codec_ctrl.hpp
- ${CMAKE_CURRENT_SOURCE_DIR}/codec_impl.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/dboard_impl.cpp
${CMAKE_CURRENT_SOURCE_DIR}/dboard_iface.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/dsp_impl.cpp
${CMAKE_CURRENT_SOURCE_DIR}/io_impl.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/mboard_impl.cpp
${CMAKE_CURRENT_SOURCE_DIR}/soft_time_ctrl.cpp
${CMAKE_CURRENT_SOURCE_DIR}/usrp1_iface.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/usrp1_iface.hpp
${CMAKE_CURRENT_SOURCE_DIR}/usrp1_impl.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/usrp1_impl.hpp
)
ENDIF(ENABLE_USRP1)
diff --git a/host/lib/usrp/usrp1/codec_ctrl.cpp b/host/lib/usrp/usrp1/codec_ctrl.cpp
index 448135185..2e9355063 100644
--- a/host/lib/usrp/usrp1/codec_ctrl.cpp
+++ b/host/lib/usrp/usrp1/codec_ctrl.cpp
@@ -43,9 +43,7 @@ const gain_range_t usrp1_codec_ctrl::rx_pga_gain_range(0, 20, 1);
class usrp1_codec_ctrl_impl : public usrp1_codec_ctrl {
public:
//structors
- usrp1_codec_ctrl_impl(usrp1_iface::sptr iface,
- usrp1_clock_ctrl::sptr clock,
- int spi_slave);
+ usrp1_codec_ctrl_impl(spi_iface::sptr iface, int spi_slave);
~usrp1_codec_ctrl_impl(void);
//aux adc and dac control
@@ -53,7 +51,7 @@ public:
void write_aux_dac(aux_dac_t which, double volts);
//duc control
- void set_duc_freq(double freq);
+ void set_duc_freq(double freq, double);
void enable_tx_digital(bool enb);
//pga gain control
@@ -66,8 +64,7 @@ public:
void bypass_adc_buffers(bool bypass);
private:
- usrp1_iface::sptr _iface;
- usrp1_clock_ctrl::sptr _clock_ctrl;
+ spi_iface::sptr _iface;
int _spi_slave;
ad9862_regs_t _ad9862_regs;
void send_reg(boost::uint8_t addr);
@@ -80,12 +77,8 @@ private:
/***********************************************************************
* Codec Control Structors
**********************************************************************/
-usrp1_codec_ctrl_impl::usrp1_codec_ctrl_impl(usrp1_iface::sptr iface,
- usrp1_clock_ctrl::sptr clock,
- int spi_slave)
-{
+usrp1_codec_ctrl_impl::usrp1_codec_ctrl_impl(spi_iface::sptr iface, int spi_slave){
_iface = iface;
- _clock_ctrl = clock;
_spi_slave = spi_slave;
//soft reset
@@ -381,9 +374,9 @@ double usrp1_codec_ctrl_impl::fine_tune(double codec_rate, double target_freq)
return actual_freq;
}
-void usrp1_codec_ctrl_impl::set_duc_freq(double freq)
+void usrp1_codec_ctrl_impl::set_duc_freq(double freq, double rate)
{
- double codec_rate = _clock_ctrl->get_master_clock_freq() * 2;
+ double codec_rate = rate * 2;
double coarse_freq = coarse_tune(codec_rate, freq);
double fine_freq = fine_tune(codec_rate / 4, freq - coarse_freq);
@@ -421,9 +414,8 @@ void usrp1_codec_ctrl_impl::bypass_adc_buffers(bool bypass) {
/***********************************************************************
* Codec Control Make
**********************************************************************/
-usrp1_codec_ctrl::sptr usrp1_codec_ctrl::make(usrp1_iface::sptr iface,
- usrp1_clock_ctrl::sptr clock,
+usrp1_codec_ctrl::sptr usrp1_codec_ctrl::make(spi_iface::sptr iface,
int spi_slave)
{
- return sptr(new usrp1_codec_ctrl_impl(iface, clock, spi_slave));
+ return sptr(new usrp1_codec_ctrl_impl(iface, spi_slave));
}
diff --git a/host/lib/usrp/usrp1/codec_ctrl.hpp b/host/lib/usrp/usrp1/codec_ctrl.hpp
index 20e4015c5..70f4e0b61 100644
--- a/host/lib/usrp/usrp1/codec_ctrl.hpp
+++ b/host/lib/usrp/usrp1/codec_ctrl.hpp
@@ -18,8 +18,7 @@
#ifndef INCLUDED_USRP1_CODEC_CTRL_HPP
#define INCLUDED_USRP1_CODEC_CTRL_HPP
-#include "usrp1_iface.hpp"
-#include "clock_ctrl.hpp"
+#include <uhd/types/serial.hpp>
#include <uhd/types/ranges.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/utility.hpp>
@@ -38,13 +37,10 @@ public:
/*!
* Make a new clock control object.
- * \param iface the usrp1 iface object
+ * \param iface the spi iface object
* \param spi_slave which spi device
- * \return the clock control object
*/
- static sptr make(usrp1_iface::sptr iface,
- usrp1_clock_ctrl::sptr clock, int spi_slave
- );
+ static sptr make(uhd::spi_iface::sptr iface, int spi_slave);
//! aux adc identifier constants
enum aux_adc_t{
@@ -91,7 +87,7 @@ public:
virtual double get_rx_pga_gain(char which) = 0;
//! Set the TX modulator frequency
- virtual void set_duc_freq(double freq) = 0;
+ virtual void set_duc_freq(double freq, double rate) = 0;
//! Enable or disable the digital part of the DAC
virtual void enable_tx_digital(bool enb) = 0;
diff --git a/host/lib/usrp/usrp1/dboard_iface.cpp b/host/lib/usrp/usrp1/dboard_iface.cpp
index 3f3a98b7a..449ec64fe 100644
--- a/host/lib/usrp/usrp1/dboard_iface.cpp
+++ b/host/lib/usrp/usrp1/dboard_iface.cpp
@@ -20,7 +20,6 @@
#include "fpga_regs_common.h"
#include "usrp_spi_defs.h"
#include "fpga_regs_standard.h"
-#include "clock_ctrl.hpp"
#include "codec_ctrl.hpp"
#include <uhd/usrp/dboard_iface.hpp>
#include <uhd/types/dict.hpp>
@@ -38,16 +37,16 @@ class usrp1_dboard_iface : public dboard_iface {
public:
usrp1_dboard_iface(usrp1_iface::sptr iface,
- usrp1_clock_ctrl::sptr clock,
usrp1_codec_ctrl::sptr codec,
usrp1_impl::dboard_slot_t dboard_slot,
+ const double master_clock_rate,
const dboard_id_t &rx_dboard_id
):
_dboard_slot(dboard_slot),
+ _master_clock_rate(master_clock_rate),
_rx_dboard_id(rx_dboard_id)
{
_iface = iface;
- _clock = clock;
_codec = codec;
//init the clock rate shadows
@@ -103,24 +102,24 @@ public:
private:
usrp1_iface::sptr _iface;
- usrp1_clock_ctrl::sptr _clock;
usrp1_codec_ctrl::sptr _codec;
uhd::dict<unit_t, double> _clock_rates;
const usrp1_impl::dboard_slot_t _dboard_slot;
- const dboard_id_t &_rx_dboard_id;
+ const double _master_clock_rate;
+ const dboard_id_t _rx_dboard_id;
};
/***********************************************************************
* Make Function
**********************************************************************/
dboard_iface::sptr usrp1_impl::make_dboard_iface(usrp1_iface::sptr iface,
- usrp1_clock_ctrl::sptr clock,
usrp1_codec_ctrl::sptr codec,
- dboard_slot_t dboard_slot,
+ usrp1_impl::dboard_slot_t dboard_slot,
+ const double master_clock_rate,
const dboard_id_t &rx_dboard_id
){
return dboard_iface::sptr(new usrp1_dboard_iface(
- iface, clock, codec, dboard_slot, rx_dboard_id
+ iface, codec, dboard_slot, master_clock_rate, rx_dboard_id
));
}
@@ -141,7 +140,7 @@ void usrp1_dboard_iface::set_clock_rate(unit_t unit, double rate)
_clock_rates[unit] = rate;
if (unit == UNIT_RX && _rx_dboard_id == dbsrx_classic_id){
- size_t divider = size_t(_clock->get_master_clock_freq()/rate);
+ size_t divider = size_t(_master_clock_rate/rate);
switch(_dboard_slot){
case usrp1_impl::DBOARD_SLOT_A:
_iface->poke32(FR_RX_A_REFCLK, (divider & 0x7f) | 0x80);
@@ -159,10 +158,10 @@ std::vector<double> usrp1_dboard_iface::get_clock_rates(unit_t unit)
std::vector<double> rates;
if (unit == UNIT_RX && _rx_dboard_id == dbsrx_classic_id){
for (size_t div = 1; div <= 127; div++)
- rates.push_back(_clock->get_master_clock_freq() / div);
+ rates.push_back(_master_clock_rate / div);
}
else{
- rates.push_back(_clock->get_master_clock_freq());
+ rates.push_back(_master_clock_rate);
}
return rates;
}
@@ -178,7 +177,7 @@ void usrp1_dboard_iface::set_clock_enabled(unit_t, bool)
}
double usrp1_dboard_iface::get_codec_rate(unit_t){
- return _clock->get_master_clock_freq();
+ return _master_clock_rate;
}
/***********************************************************************
diff --git a/host/lib/usrp/usrp1/io_impl.cpp b/host/lib/usrp/usrp1/io_impl.cpp
index 90ed17cd8..9de11e0ea 100644
--- a/host/lib/usrp/usrp1/io_impl.cpp
+++ b/host/lib/usrp/usrp1/io_impl.cpp
@@ -18,23 +18,21 @@
#define SRPH_DONT_CHECK_SEQUENCE
#include "../../transport/super_recv_packet_handler.hpp"
#include "../../transport/super_send_packet_handler.hpp"
+#include "usrp1_calc_mux.hpp"
+#include "fpga_regs_standard.h"
#include "usrp_commands.h"
#include "usrp1_impl.hpp"
#include <uhd/utils/msg.hpp>
#include <uhd/utils/safe_call.hpp>
-#include <uhd/utils/thread_priority.hpp>
-#include <uhd/usrp/dsp_props.hpp>
#include <uhd/transport/bounded_buffer.hpp>
+#include <boost/math/special_functions/sign.hpp>
+#include <boost/math/special_functions/round.hpp>
#include <boost/bind.hpp>
#include <boost/format.hpp>
-#include <boost/asio.hpp>
-#include <boost/bind.hpp>
-#include <boost/thread.hpp>
using namespace uhd;
using namespace uhd::usrp;
using namespace uhd::transport;
-namespace asio = boost::asio;
static const size_t alignment_padding = 512;
@@ -145,6 +143,8 @@ struct usrp1_impl::io_impl{
//state management for overflow and underflow
size_t underflow_poll_samp_count;
size_t overflow_poll_samp_count;
+ size_t rx_samps_per_poll_interval;
+ size_t tx_samps_per_poll_interval;
//wrapper around the actual send buffer interface
//all of this to ensure only aligned lengths are committed
@@ -230,41 +230,21 @@ void usrp1_impl::io_init(void){
_io_impl = UHD_PIMPL_MAKE(io_impl, (_data_transport));
- _soft_time_ctrl = soft_time_ctrl::make(
- boost::bind(&usrp1_impl::rx_stream_on_off, this, _1)
- );
-
- this->enable_tx(true); //always enabled
- rx_stream_on_off(false);
- _io_impl->flush_send_buff();
-
- //update mapping here since it didnt b4 when io init not called first
- update_xport_channel_mapping();
-}
-
-void usrp1_impl::update_xport_channel_mapping(void){
- if (_io_impl.get() == NULL) return; //not inited yet
-
- //set all of the relevant properties on the handler
- boost::mutex::scoped_lock recv_lock = _io_impl->recv_handler.get_scoped_lock();
+ //init some handler stuff
+ _io_impl->recv_handler.set_tick_rate(_master_clock_rate);
_io_impl->recv_handler.set_vrt_unpacker(&usrp1_bs_vrt_unpacker);
- _io_impl->recv_handler.set_tick_rate(_clock_ctrl->get_master_clock_freq());
- _io_impl->recv_handler.set_samp_rate(_rx_dsp_proxies[_rx_dsp_proxies.keys().at(0)]->get_link()[DSP_PROP_HOST_RATE].as<double>());
_io_impl->recv_handler.set_xport_chan_get_buff(0, boost::bind(
&uhd::transport::zero_copy_if::get_recv_buff, _io_impl->data_transport, _1
));
- _io_impl->recv_handler.set_converter(_rx_otw_type, _rx_subdev_spec.size());
-
- //set all of the relevant properties on the handler
- boost::mutex::scoped_lock send_lock = _io_impl->send_handler.get_scoped_lock();
+ _io_impl->send_handler.set_tick_rate(_master_clock_rate);
_io_impl->send_handler.set_vrt_packer(&usrp1_bs_vrt_packer);
- _io_impl->send_handler.set_tick_rate(_clock_ctrl->get_master_clock_freq());
- _io_impl->send_handler.set_samp_rate(_tx_dsp_proxies[_tx_dsp_proxies.keys().at(0)]->get_link()[DSP_PROP_HOST_RATE].as<double>());
_io_impl->send_handler.set_xport_chan_get_buff(0, boost::bind(
&usrp1_impl::io_impl::get_send_buff, _io_impl.get(), _1
));
- _io_impl->send_handler.set_converter(_tx_otw_type, _tx_subdev_spec.size());
- _io_impl->send_handler.set_max_samples_per_packet(get_max_send_samps_per_packet());
+
+ this->enable_tx(true); //always enabled
+ rx_stream_on_off(false);
+ _io_impl->flush_send_buff();
}
void usrp1_impl::rx_stream_on_off(bool enb){
@@ -276,6 +256,125 @@ void usrp1_impl::rx_stream_on_off(bool enb){
}
/***********************************************************************
+ * Properties callback methods below
+ **********************************************************************/
+void usrp1_impl::update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){
+ //sanity checking
+ if (spec.size() == 0) throw uhd::value_error("rx subdev spec cant be empty");
+ if (spec.size() > get_num_ddcs()) throw uhd::value_error("rx subdev spec too long");
+
+ _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){
+ //sanity checking
+ if (spec.size() == 0) throw uhd::value_error("tx subdev spec cant be empty");
+ if (spec.size() > get_num_ducs()) throw uhd::value_error("tx subdev spec too long");
+
+ _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){
+ size_t rate = boost::math::iround(_master_clock_rate / samp_rate);
+
+ //clip the rate to something in range:
+ rate = std::min<size_t>(std::max<size_t>(rate, 4), 256);
+
+ //TODO Poll every 100ms. Make it selectable?
+ _io_impl->rx_samps_per_poll_interval = size_t(0.1 * _master_clock_rate / rate);
+
+ 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){
+ size_t rate = boost::math::iround(_master_clock_rate / samp_rate);
+
+ //clip the rate to something in range:
+ rate = std::min<size_t>(std::max<size_t>(rate, 4), 256);
+
+ //TODO Poll every 100ms. Make it selectable?
+ _io_impl->tx_samps_per_poll_interval = size_t(0.1 * _master_clock_rate / rate);
+
+ 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(uhd::async_metadata_t &, double timeout){
+ //dummy fill-in for the recv_async_msg
+ boost::this_thread::sleep(boost::posix_time::microseconds(long(timeout*1e6)));
+ return false;
+}
+
+/***********************************************************************
* Data send + helper functions
**********************************************************************/
size_t usrp1_impl::get_max_send_samps_per_packet(void) const {
@@ -306,10 +405,10 @@ size_t usrp1_impl::send(
//handle the polling for underflow conditions
_io_impl->underflow_poll_samp_count += num_samps_sent;
- if (_io_impl->underflow_poll_samp_count >= _tx_samps_per_poll_interval){
+ if (_io_impl->underflow_poll_samp_count >= _io_impl->tx_samps_per_poll_interval){
_io_impl->underflow_poll_samp_count = 0; //reset count
boost::uint8_t underflow = 0;
- ssize_t ret = _ctrl_transport->usrp_control_read(
+ int ret = _fx2_ctrl->usrp_control_read(
VRQ_GET_STATUS, 0, GS_TX_UNDERRUN,
&underflow, sizeof(underflow)
);
@@ -345,10 +444,10 @@ size_t usrp1_impl::recv(
//handle the polling for overflow conditions
_io_impl->overflow_poll_samp_count += num_samps_recvd;
- if (_io_impl->overflow_poll_samp_count >= _rx_samps_per_poll_interval){
+ if (_io_impl->overflow_poll_samp_count >= _io_impl->rx_samps_per_poll_interval){
_io_impl->overflow_poll_samp_count = 0; //reset count
boost::uint8_t overflow = 0;
- ssize_t ret = _ctrl_transport->usrp_control_read(
+ int ret = _fx2_ctrl->usrp_control_read(
VRQ_GET_STATUS, 0, GS_RX_OVERRUN,
&overflow, sizeof(overflow)
);
diff --git a/host/lib/usrp/usrp1/usrp1_calc_mux.hpp b/host/lib/usrp/usrp1/usrp1_calc_mux.hpp
new file mode 100644
index 000000000..31c190db0
--- /dev/null
+++ b/host/lib/usrp/usrp1/usrp1_calc_mux.hpp
@@ -0,0 +1,156 @@
+//
+// Copyright 2010-2011 Ettus Research LLC
+//
+// This program is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program. If not, see <http://www.gnu.org/licenses/>.
+//
+
+#include <uhd/config.hpp>
+#include <uhd/exception.hpp>
+#include <uhd/types/dict.hpp>
+#include <uhd/utils/algorithm.hpp>
+#include <boost/assign/list_of.hpp>
+#include <boost/format.hpp>
+#include <utility>
+#include <vector>
+#include <string>
+
+#ifndef INCLUDED_USRP1_CALC_MUX_HPP
+#define INCLUDED_USRP1_CALC_MUX_HPP
+
+//db_name, conn_type for the mux calculations below...
+typedef std::pair<std::string, std::string> mapping_pair_t;
+
+/***********************************************************************
+ * Calculate the RX mux value:
+ * The I and Q mux values are intentionally reversed to flip I and Q
+ * to account for the reversal in the type conversion routines.
+ **********************************************************************/
+static int calc_rx_mux_pair(int adc_for_i, int adc_for_q){
+ return (adc_for_i << 2) | (adc_for_q << 0); //shift reversal here
+}
+
+/*!
+ * 3 2 1 0
+ * 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0
+ * +-----------------------+-------+-------+-------+-------+-+-----+
+ * | must be zero | Q3| I3| Q2| I2| Q1| I1| Q0| I0|Z| NCH |
+ * +-----------------------+-------+-------+-------+-------+-+-----+
+ */
+static boost::uint32_t calc_rx_mux(const std::vector<mapping_pair_t> &mapping){
+ //create look-up-table for mapping dboard name and connection type to ADC flags
+ static const int ADC0 = 0, ADC1 = 1, ADC2 = 2, ADC3 = 3;
+ static const uhd::dict<std::string, uhd::dict<std::string, int> > name_to_conn_to_flag = boost::assign::map_list_of
+ ("A", boost::assign::map_list_of
+ ("IQ", calc_rx_mux_pair(ADC0, ADC1)) //I and Q
+ ("QI", calc_rx_mux_pair(ADC1, ADC0)) //I and Q
+ ("I", calc_rx_mux_pair(ADC0, ADC0)) //I and Q (Q identical but ignored Z=1)
+ ("Q", calc_rx_mux_pair(ADC1, ADC1)) //I and Q (Q identical but ignored Z=1)
+ )
+ ("B", boost::assign::map_list_of
+ ("IQ", calc_rx_mux_pair(ADC2, ADC3)) //I and Q
+ ("QI", calc_rx_mux_pair(ADC3, ADC2)) //I and Q
+ ("I", calc_rx_mux_pair(ADC2, ADC2)) //I and Q (Q identical but ignored Z=1)
+ ("Q", calc_rx_mux_pair(ADC3, ADC3)) //I and Q (Q identical but ignored Z=1)
+ )
+ ;
+
+ //extract the number of channels
+ const size_t nchan = mapping.size();
+
+ //calculate the channel flags
+ int channel_flags = 0;
+ size_t num_reals = 0, num_quads = 0;
+ BOOST_FOREACH(const mapping_pair_t &pair, uhd::reversed(mapping)){
+ const std::string name = pair.first, conn = pair.second;
+ if (conn == "IQ" or conn == "QI") num_quads++;
+ if (conn == "I" or conn == "Q") num_reals++;
+ channel_flags = (channel_flags << 4) | name_to_conn_to_flag[name][conn];
+ }
+
+ //calculate Z:
+ // for all real sources: Z = 1
+ // for all quadrature sources: Z = 0
+ // for mixed sources: warning + Z = 0
+ int Z = (num_quads > 0)? 0 : 1;
+ if (num_quads != 0 and num_reals != 0) UHD_MSG(warning) << boost::format(
+ "Mixing real and quadrature rx subdevices is not supported.\n"
+ "The Q input to the real source(s) will be non-zero.\n"
+ );
+
+ //calculate the rx mux value
+ return ((channel_flags & 0xffff) << 4) | ((Z & 0x1) << 3) | ((nchan & 0x7) << 0);
+}
+
+/***********************************************************************
+ * Calculate the TX mux value:
+ * The I and Q mux values are intentionally reversed to flip I and Q
+ * to account for the reversal in the type conversion routines.
+ **********************************************************************/
+static int calc_tx_mux_pair(int chn_for_i, int chn_for_q){
+ return (chn_for_i << 4) | (chn_for_q << 0); //shift reversal here
+}
+
+/*!
+ * 3 2 1 0
+ * 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0
+ * +-----------------------+-------+-------+-------+-------+-+-----+
+ * | | DAC1Q | DAC1I | DAC0Q | DAC0I |0| NCH |
+ * +-----------------------------------------------+-------+-+-----+
+ */
+static boost::uint32_t calc_tx_mux(const std::vector<mapping_pair_t> &mapping){
+ //create look-up-table for mapping channel number and connection type to flags
+ static const int ENB = 1 << 3, CHAN_I0 = 0, CHAN_Q0 = 1, CHAN_I1 = 2, CHAN_Q1 = 3;
+ static const uhd::dict<size_t, uhd::dict<std::string, int> > chan_to_conn_to_flag = boost::assign::map_list_of
+ (0, boost::assign::map_list_of
+ ("IQ", calc_tx_mux_pair(CHAN_I0 | ENB, CHAN_Q0 | ENB))
+ ("QI", calc_tx_mux_pair(CHAN_Q0 | ENB, CHAN_I0 | ENB))
+ ("I", calc_tx_mux_pair(CHAN_I0 | ENB, 0 ))
+ ("Q", calc_tx_mux_pair(0, CHAN_I0 | ENB))
+ )
+ (1, boost::assign::map_list_of
+ ("IQ", calc_tx_mux_pair(CHAN_I1 | ENB, CHAN_Q1 | ENB))
+ ("QI", calc_tx_mux_pair(CHAN_Q1 | ENB, CHAN_I1 | ENB))
+ ("I", calc_tx_mux_pair(CHAN_I1 | ENB, 0 ))
+ ("Q", calc_tx_mux_pair(0, CHAN_I1 | ENB))
+ )
+ ;
+
+ //extract the number of channels
+ size_t nchan = mapping.size();
+
+ //calculate the channel flags
+ int channel_flags = 0, chan = 0;
+ uhd::dict<std::string, int> slot_to_chan_count = boost::assign::map_list_of("A", 0)("B", 0);
+ BOOST_FOREACH(const mapping_pair_t &pair, mapping){
+ const std::string name = pair.first, conn = pair.second;
+
+ //combine the channel flags: shift for slot A vs B
+ if (name == "A") channel_flags |= chan_to_conn_to_flag[chan][conn] << 0;
+ if (name == "B") channel_flags |= chan_to_conn_to_flag[chan][conn] << 8;
+
+ //sanity check, only 1 channel per slot
+ slot_to_chan_count[name]++;
+ if (slot_to_chan_count[name] > 1) throw uhd::value_error(
+ "cannot assign dboard slot to multiple channels: " + name
+ );
+
+ //increment for the next channel
+ chan++;
+ }
+
+ //calculate the tx mux value
+ return ((channel_flags & 0xffff) << 4) | ((nchan & 0x7) << 0);
+}
+
+#endif /* INCLUDED_USRP1_CALC_MUX_HPP */
diff --git a/host/lib/usrp/usrp1/usrp1_iface.cpp b/host/lib/usrp/usrp1/usrp1_iface.cpp
index 8877f19db..c790aecb4 100644
--- a/host/lib/usrp/usrp1/usrp1_iface.cpp
+++ b/host/lib/usrp/usrp1/usrp1_iface.cpp
@@ -36,7 +36,6 @@ public:
usrp1_iface_impl(uhd::usrp::fx2_ctrl::sptr ctrl_transport)
{
_ctrl_transport = ctrl_transport;
- mb_eeprom = mboard_eeprom_t(*this, mboard_eeprom_t::MAP_B000);
}
~usrp1_iface_impl(void)
@@ -102,78 +101,16 @@ public:
throw uhd::not_implemented_error("Unhandled command peek16()");
return 0;
}
-
- void write_uart(boost::uint8_t, const std::string &) {
- throw uhd::not_implemented_error("Unhandled command write_uart()");
- }
-
- std::string read_uart(boost::uint8_t) {
- throw uhd::not_implemented_error("Unhandled command read_uart()");
- }
/*******************************************************************
* I2C
******************************************************************/
- static const size_t max_i2c_data_bytes = 64;
-
- //TODO: make this handle EEPROM page sizes. right now you can't write over a 16-byte boundary.
- //to accomplish this you'll have to have addr offset as a separate parameter.
-
- void write_i2c(boost::uint8_t addr, const byte_vector_t &bytes)
- {
- UHD_LOGV(always) << "write_i2c:" << std::endl
- << " addr 0x" << std::hex << int(addr) << std::endl
- << " len " << bytes.size() << std::endl
- ;
- UHD_ASSERT_THROW(bytes.size() < max_i2c_data_bytes);
-
- unsigned char buff[max_i2c_data_bytes];
- std::copy(bytes.begin(), bytes.end(), buff);
-
- int ret = _ctrl_transport->usrp_i2c_write(addr & 0xff,
- buff,
- bytes.size());
-
- // TODO throw and catch i2c failures during eeprom read
- if (ret < 0)
- UHD_LOGV(often) << "USRP: failed i2c write: " << ret << std::endl;
+ void write_i2c(boost::uint8_t addr, const byte_vector_t &bytes){
+ return _ctrl_transport->write_i2c(addr, bytes);
}
- byte_vector_t read_i2c(boost::uint8_t addr, size_t num_bytes)
- {
- UHD_LOGV(always) << "read_i2c:" << std::endl
- << " addr 0x" << std::hex << int(addr) << std::endl
- << " len " << num_bytes << std::endl
- ;
- UHD_ASSERT_THROW(num_bytes < max_i2c_data_bytes);
-
- unsigned char buff[max_i2c_data_bytes];
- int ret = _ctrl_transport->usrp_i2c_read(addr & 0xff,
- buff,
- num_bytes);
-
- // TODO throw and catch i2c failures during eeprom read
- if (ret < 0 or (unsigned)ret < num_bytes) {
- UHD_LOGV(often) << "USRP: failed i2c read: " << ret << std::endl;
- return byte_vector_t(num_bytes, 0xff);
- }
-
- byte_vector_t out_bytes;
- for (size_t i = 0; i < num_bytes; i++)
- out_bytes.push_back(buff[i]);
-
- return out_bytes;
- }
-
- //! overload read_eeprom to handle multi-byte reads
- byte_vector_t read_eeprom(
- boost::uint8_t addr,
- boost::uint8_t offset,
- size_t num_bytes
- ){
- //do a zero byte write to start read cycle
- this->write_i2c(addr, byte_vector_t(1, offset));
- return this->read_i2c(addr, num_bytes); //read all bytes
+ byte_vector_t read_i2c(boost::uint8_t addr, size_t num_bytes){
+ return _ctrl_transport->read_i2c(addr, num_bytes);
}
/*******************************************************************
@@ -255,37 +192,6 @@ public:
}
}
- /*******************************************************************
- * Firmware
- *
- * This call is deprecated.
- ******************************************************************/
- void write_firmware_cmd(boost::uint8_t request,
- boost::uint16_t value,
- boost::uint16_t index,
- unsigned char *buff,
- boost::uint16_t length)
- {
- int ret;
-
- if (request & 0x80) {
- ret = _ctrl_transport->usrp_control_read(request,
- value,
- index,
- buff,
- length);
- }
- else {
- ret = _ctrl_transport->usrp_control_write(request,
- value,
- index,
- buff,
- length);
- }
-
- if (ret < 0) throw uhd::io_error("USRP1: failed firmware command");
- }
-
private:
uhd::usrp::fx2_ctrl::sptr _ctrl_transport;
};
diff --git a/host/lib/usrp/usrp1/usrp1_iface.hpp b/host/lib/usrp/usrp1/usrp1_iface.hpp
index e480c22ea..3da754a87 100644
--- a/host/lib/usrp/usrp1/usrp1_iface.hpp
+++ b/host/lib/usrp/usrp1/usrp1_iface.hpp
@@ -18,7 +18,8 @@
#ifndef INCLUDED_USRP1_IFACE_HPP
#define INCLUDED_USRP1_IFACE_HPP
-#include <uhd/usrp/mboard_iface.hpp>
+#include "wb_iface.hpp"
+#include <uhd/types/serial.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/utility.hpp>
#include "../fx2/fx2_ctrl.hpp"
@@ -28,33 +29,16 @@
* Provides a set of functions to implementation layer.
* Including spi, peek, poke, control...
*/
-class usrp1_iface : public uhd::usrp::mboard_iface, boost::noncopyable{
+class usrp1_iface : public wb_iface, public uhd::i2c_iface, public uhd::spi_iface, boost::noncopyable{
public:
typedef boost::shared_ptr<usrp1_iface> sptr;
- //motherboard eeprom map structure
- uhd::usrp::mboard_eeprom_t mb_eeprom;
-
/*!
* Make a new usrp1 interface with the control transport.
* \param ctrl_transport the usrp controller object
* \return a new usrp1 interface object
*/
static sptr make(uhd::usrp::fx2_ctrl::sptr ctrl_transport);
-
- /*!
- * Perform a general USB firmware OUT operation
- * \param request
- * \param value
- * \param index
- * \param data
- * \return
- */
- virtual void write_firmware_cmd(boost::uint8_t request,
- boost::uint16_t value,
- boost::uint16_t index,
- unsigned char* buff,
- boost::uint16_t length) = 0;
};
#endif /* INCLUDED_USRP1_IFACE_HPP */
diff --git a/host/lib/usrp/usrp1/usrp1_impl.cpp b/host/lib/usrp/usrp1/usrp1_impl.cpp
index a3d502038..5d3c5a00a 100644
--- a/host/lib/usrp/usrp1/usrp1_impl.cpp
+++ b/host/lib/usrp/usrp1/usrp1_impl.cpp
@@ -16,13 +16,14 @@
//
#include "usrp1_impl.hpp"
-#include "fpga_regs_standard.h"
#include "usrp_spi_defs.h"
+#include "usrp_commands.h"
+#include "fpga_regs_standard.h"
+#include "fpga_regs_common.h"
+#include "usrp_i2c_addr.h"
#include <uhd/utils/log.hpp>
#include <uhd/utils/safe_call.hpp>
#include <uhd/transport/usb_control.hpp>
-#include <uhd/usrp/device_props.hpp>
-#include <uhd/usrp/mboard_props.hpp>
#include <uhd/utils/msg.hpp>
#include <uhd/exception.hpp>
#include <uhd/utils/static.hpp>
@@ -101,10 +102,11 @@ static device_addrs_t usrp1_find(const device_addr_t &hint)
try{control = usb_control::make(handle);}
catch(const uhd::exception &){continue;} //ignore claimed
- usrp1_iface::sptr iface = usrp1_iface::make(fx2_ctrl::make(control));
+ fx2_ctrl::sptr fx2_ctrl = fx2_ctrl::make(control);
+ const mboard_eeprom_t mb_eeprom(*fx2_ctrl, mboard_eeprom_t::MAP_B000);
device_addr_t new_addr;
new_addr["type"] = "usrp1";
- new_addr["name"] = iface->mb_eeprom["name"];
+ new_addr["name"] = mb_eeprom["name"];
new_addr["serial"] = handle->get_serial();
//this is a found usrp1 when the hint serial and name match or blank
if (
@@ -122,6 +124,17 @@ static device_addrs_t usrp1_find(const device_addr_t &hint)
* Make
**********************************************************************/
static device::sptr usrp1_make(const device_addr_t &device_addr){
+ return device::sptr(new usrp1_impl(device_addr));
+}
+
+UHD_STATIC_BLOCK(register_usrp1_device){
+ device::register_device(&usrp1_find, &usrp1_make);
+}
+
+/***********************************************************************
+ * Structors
+ **********************************************************************/
+usrp1_impl::usrp1_impl(const device_addr_t &device_addr){
UHD_MSG(status) << "Opening a USRP1 device..." << std::endl;
//extract the FPGA path for the USRP1
@@ -144,67 +157,232 @@ static device::sptr usrp1_make(const device_addr_t &device_addr){
}
UHD_ASSERT_THROW(handle.get() != NULL); //better be found
- //create control objects and a data transport
- usb_control::sptr ctrl_transport = usb_control::make(handle);
- fx2_ctrl::sptr usrp_ctrl = fx2_ctrl::make(ctrl_transport);
- usrp_ctrl->usrp_load_fpga(usrp1_fpga_image);
- usrp_ctrl->usrp_init();
- usb_zero_copy::sptr data_transport = usb_zero_copy::make(
+ ////////////////////////////////////////////////////////////////////
+ // Create controller objects
+ ////////////////////////////////////////////////////////////////////
+ //usb_control::sptr usb_ctrl = usb_control::make(handle);
+ _fx2_ctrl = fx2_ctrl::make(usb_control::make(handle));
+ _fx2_ctrl->usrp_load_fpga(usrp1_fpga_image);
+ _fx2_ctrl->usrp_init();
+ _data_transport = usb_zero_copy::make(
handle, // identifier
6, // IN endpoint
2, // OUT endpoint
device_addr // param hints
);
-
- //create the usrp1 implementation guts
- return device::sptr(new usrp1_impl(data_transport, usrp_ctrl));
-}
-
-UHD_STATIC_BLOCK(register_usrp1_device){
- device::register_device(&usrp1_find, &usrp1_make);
-}
-
-/***********************************************************************
- * Structors
- **********************************************************************/
-usrp1_impl::usrp1_impl(uhd::transport::usb_zero_copy::sptr data_transport,
- uhd::usrp::fx2_ctrl::sptr ctrl_transport)
- : _data_transport(data_transport), _ctrl_transport(ctrl_transport)
-{
- _iface = usrp1_iface::make(ctrl_transport);
-
- //create clock interface
- _clock_ctrl = usrp1_clock_ctrl::make(_iface);
-
- //create codec interface
- _codec_ctrls[DBOARD_SLOT_A] = usrp1_codec_ctrl::make(
- _iface, _clock_ctrl, SPI_ENABLE_CODEC_A
- );
- _codec_ctrls[DBOARD_SLOT_B] = usrp1_codec_ctrl::make(
- _iface, _clock_ctrl, SPI_ENABLE_CODEC_B
+ _iface = usrp1_iface::make(_fx2_ctrl);
+ _soft_time_ctrl = soft_time_ctrl::make(
+ boost::bind(&usrp1_impl::rx_stream_on_off, this, _1)
);
+ _dbc["A"]; _dbc["B"]; //ensure that keys exist
+
+ // Normal mode with no loopback or Rx counting
+ _iface->poke32(FR_MODE, 0x00000000);
+ _iface->poke32(FR_DEBUG_EN, 0x00000000);
+ _iface->poke32(FR_RX_SAMPLE_RATE_DIV, 0x00000001); //divide by 2
+ _iface->poke32(FR_TX_SAMPLE_RATE_DIV, 0x00000001); //divide by 2
+ _iface->poke32(FR_DC_OFFSET_CL_EN, 0x0000000f);
+
+ // Reset offset correction registers
+ _iface->poke32(FR_ADC_OFFSET_0, 0x00000000);
+ _iface->poke32(FR_ADC_OFFSET_1, 0x00000000);
+ _iface->poke32(FR_ADC_OFFSET_2, 0x00000000);
+ _iface->poke32(FR_ADC_OFFSET_3, 0x00000000);
+
+ // Set default for RX format to 16-bit I&Q and no half-band filter bypass
+ _iface->poke32(FR_RX_FORMAT, 0x00000300);
+
+ // Set default for TX format to 16-bit I&Q
+ _iface->poke32(FR_TX_FORMAT, 0x00000000);
+
+ UHD_LOG
+ << "USRP1 Capabilities" << std::endl
+ << " number of duc's: " << get_num_ddcs() << std::endl
+ << " number of ddc's: " << get_num_ducs() << std::endl
+ << " rx halfband: " << has_rx_halfband() << std::endl
+ << " tx halfband: " << has_tx_halfband() << std::endl
+ ;
+
+ ////////////////////////////////////////////////////////////////////
+ // Initialize the properties tree
+ ////////////////////////////////////////////////////////////////////
+ _tree = property_tree::make();
+ _tree->create<std::string>("/name").set("USRP1 Device");
+ const property_tree::path_type mb_path = "/mboards/0";
+ _tree->create<std::string>(mb_path / "name").set("USRP1 (Classic)");
+ _tree->create<std::string>(mb_path / "load_eeprom")
+ .subscribe(boost::bind(&fx2_ctrl::usrp_load_eeprom, _fx2_ctrl, _1));
+
+ ////////////////////////////////////////////////////////////////////
+ // setup the mboard eeprom
+ ////////////////////////////////////////////////////////////////////
+ const mboard_eeprom_t mb_eeprom(*_fx2_ctrl, mboard_eeprom_t::MAP_B000);
+ _tree->create<mboard_eeprom_t>(mb_path / "eeprom")
+ .set(mb_eeprom)
+ .subscribe(boost::bind(&usrp1_impl::set_mb_eeprom, this, _1));
+
+ ////////////////////////////////////////////////////////////////////
+ // create clock control objects
+ ////////////////////////////////////////////////////////////////////
+ _master_clock_rate = 64e6;
+ try{
+ if (not mb_eeprom["mcr"].empty())
+ _master_clock_rate = boost::lexical_cast<double>(mb_eeprom["mcr"]);
+ }catch(const std::exception &e){
+ UHD_MSG(error) << "Error parsing FPGA clock rate from EEPROM: " << e.what() << std::endl;
+ }
+ UHD_MSG(status) << boost::format("Using FPGA clock rate of %fMHz...") % (_master_clock_rate/1e6) << std::endl;
+ _tree->create<double>(mb_path / "tick_rate").set(_master_clock_rate);
+
+ ////////////////////////////////////////////////////////////////////
+ // create codec control objects
+ ////////////////////////////////////////////////////////////////////
+ BOOST_FOREACH(const std::string &db, _dbc.keys()){
+ _dbc[db].codec = usrp1_codec_ctrl::make(_iface, (db == "A")? SPI_ENABLE_CODEC_A : SPI_ENABLE_CODEC_B);
+ const property_tree::path_type rx_codec_path = mb_path / "rx_codecs" / db;
+ const property_tree::path_type tx_codec_path = mb_path / "tx_codecs" / db;
+ _tree->create<std::string>(rx_codec_path / "name").set("ad9522");
+ _tree->create<meta_range_t>(rx_codec_path / "gains/pga/range").set(usrp1_codec_ctrl::rx_pga_gain_range);
+ _tree->create<double>(rx_codec_path / "gains/pga/value")
+ .coerce(boost::bind(&usrp1_impl::update_rx_codec_gain, this, db, _1));
+ _tree->create<std::string>(tx_codec_path / "name").set("ad9522");
+ _tree->create<meta_range_t>(tx_codec_path / "gains/pga/range").set(usrp1_codec_ctrl::tx_pga_gain_range);
+ _tree->create<double>(tx_codec_path / "gains/pga/value")
+ .subscribe(boost::bind(&usrp1_codec_ctrl::set_tx_pga_gain, _dbc[db].codec, _1))
+ .publish(boost::bind(&usrp1_codec_ctrl::get_tx_pga_gain, _dbc[db].codec));
+ }
- //initialize the codecs
- codec_init();
+ ////////////////////////////////////////////////////////////////////
+ // and do the misc mboard sensors
+ ////////////////////////////////////////////////////////////////////
+ //none for now...
+ _tree->create<int>(mb_path / "sensors"); //phony property so this dir exists
+
+ ////////////////////////////////////////////////////////////////////
+ // create frontend control objects
+ ////////////////////////////////////////////////////////////////////
+ _tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec")
+ .subscribe(boost::bind(&usrp1_impl::update_rx_subdev_spec, this, _1));
+ _tree->create<subdev_spec_t>(mb_path / "tx_subdev_spec")
+ .subscribe(boost::bind(&usrp1_impl::update_tx_subdev_spec, this, _1));
+
+ ////////////////////////////////////////////////////////////////////
+ // create rx dsp control objects
+ ////////////////////////////////////////////////////////////////////
+ for (size_t dspno = 0; dspno < get_num_ddcs(); dspno++){
+ property_tree::path_type rx_dsp_path = mb_path / str(boost::format("rx_dsps/%u") % dspno);
+ _tree->create<double>(rx_dsp_path / "rate/value")
+ .coerce(boost::bind(&usrp1_impl::update_rx_samp_rate, this, _1));
+ _tree->create<double>(rx_dsp_path / "freq/value")
+ .coerce(boost::bind(&usrp1_impl::update_rx_dsp_freq, this, dspno, _1));
+ _tree->create<meta_range_t>(rx_dsp_path / "freq/range")
+ .set(meta_range_t(-_master_clock_rate/2, +_master_clock_rate/2));
+ _tree->create<stream_cmd_t>(rx_dsp_path / "stream_cmd");
+ if (dspno == 0){
+ //only subscribe the callback for dspno 0 since it will stream all dsps
+ _tree->access<stream_cmd_t>(rx_dsp_path / "stream_cmd")
+ .subscribe(boost::bind(&soft_time_ctrl::issue_stream_cmd, _soft_time_ctrl, _1));
+ }
+ }
- //initialize the mboard
- mboard_init();
+ ////////////////////////////////////////////////////////////////////
+ // create tx dsp control objects
+ ////////////////////////////////////////////////////////////////////
+ for (size_t dspno = 0; dspno < get_num_ducs(); dspno++){
+ property_tree::path_type tx_dsp_path = mb_path / str(boost::format("tx_dsps/%u") % dspno);
+ _tree->create<double>(tx_dsp_path / "rate/value")
+ .coerce(boost::bind(&usrp1_impl::update_tx_samp_rate, this, _1));
+ _tree->create<double>(tx_dsp_path / "freq/value")
+ .coerce(boost::bind(&usrp1_impl::update_tx_dsp_freq, this, dspno, _1));
+ _tree->create<meta_range_t>(tx_dsp_path / "freq/range")
+ .set(meta_range_t(-_master_clock_rate/2, +_master_clock_rate/2));
+ }
- //initialize the dboards
- dboard_init();
+ ////////////////////////////////////////////////////////////////////
+ // create time control objects
+ ////////////////////////////////////////////////////////////////////
+ _tree->create<time_spec_t>(mb_path / "time/now")
+ .publish(boost::bind(&soft_time_ctrl::get_time, _soft_time_ctrl))
+ .subscribe(boost::bind(&soft_time_ctrl::set_time, _soft_time_ctrl, _1));
+
+ _tree->create<std::vector<std::string> >(mb_path / "ref_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 / "ref_source/value").set("internal");
+ _tree->create<std::string>(mb_path / "time_source/value").set("none");
+
+ ////////////////////////////////////////////////////////////////////
+ // create dboard control objects
+ ////////////////////////////////////////////////////////////////////
+ BOOST_FOREACH(const std::string &db, _dbc.keys()){
+
+ //read the dboard eeprom to extract the dboard ids
+ dboard_eeprom_t rx_db_eeprom, tx_db_eeprom, gdb_eeprom;
+ rx_db_eeprom.load(*_fx2_ctrl, (db == "A")? (I2C_ADDR_RX_A) : (I2C_ADDR_RX_B));
+ tx_db_eeprom.load(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A) : (I2C_ADDR_TX_B));
+ gdb_eeprom.load(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A ^ 5) : (I2C_ADDR_TX_B ^ 5));
+
+ //create the properties and register subscribers
+ _tree->create<dboard_eeprom_t>(mb_path / "dboards" / db/ "rx_eeprom")
+ .set(rx_db_eeprom)
+ .subscribe(boost::bind(&usrp1_impl::set_db_eeprom, this, db, "rx", _1));
+ _tree->create<dboard_eeprom_t>(mb_path / "dboards" / db/ "tx_eeprom")
+ .set(tx_db_eeprom)
+ .subscribe(boost::bind(&usrp1_impl::set_db_eeprom, this, db, "tx", _1));
+ _tree->create<dboard_eeprom_t>(mb_path / "dboards" / db/ "gdb_eeprom")
+ .set(gdb_eeprom)
+ .subscribe(boost::bind(&usrp1_impl::set_db_eeprom, this, db, "gdb", _1));
+
+ //create a new dboard interface and manager
+ _dbc[db].dboard_iface = make_dboard_iface(
+ _iface, _dbc[db].codec,
+ (db == "A")? DBOARD_SLOT_A : DBOARD_SLOT_B,
+ _master_clock_rate, rx_db_eeprom.id
+ );
+ _tree->create<dboard_iface::sptr>(mb_path / "dboards" / db/ "iface").set(_dbc[db].dboard_iface);
+ _dbc[db].dboard_manager = dboard_manager::make(
+ rx_db_eeprom.id,
+ ((gdb_eeprom.id == dboard_id_t::none())? tx_db_eeprom : gdb_eeprom).id,
+ _dbc[db].dboard_iface
+ );
+ BOOST_FOREACH(const std::string &name, _dbc[db].dboard_manager->get_rx_subdev_names()){
+ dboard_manager::populate_prop_tree_from_subdev(
+ _tree, mb_path / "dboards" / db/ "rx_frontends" / name,
+ _dbc[db].dboard_manager->get_rx_subdev(name)
+ );
+ }
+ BOOST_FOREACH(const std::string &name, _dbc[db].dboard_manager->get_tx_subdev_names()){
+ dboard_manager::populate_prop_tree_from_subdev(
+ _tree, mb_path / "dboards" / db/ "tx_frontends" / name,
+ _dbc[db].dboard_manager->get_tx_subdev(name)
+ );
+ }
- //initialize the dsps
- rx_dsp_init();
+ //init the subdev specs if we have a dboard (wont leave this loop empty)
+ if (rx_db_eeprom.id != dboard_id_t::none() or _rx_subdev_spec.empty()){
+ _rx_subdev_spec = subdev_spec_t(db + ":" + _dbc[db].dboard_manager->get_rx_subdev_names()[0]);
+ }
+ if (tx_db_eeprom.id != dboard_id_t::none() or _tx_subdev_spec.empty()){
+ _tx_subdev_spec = subdev_spec_t(db + ":" + _dbc[db].dboard_manager->get_tx_subdev_names()[0]);
+ }
+ }
- //initialize the dsps
- tx_dsp_init();
+ //initialize io handling
+ this->io_init();
- //init the subdev specs
- this->mboard_set(MBOARD_PROP_RX_SUBDEV_SPEC, subdev_spec_t());
- this->mboard_set(MBOARD_PROP_TX_SUBDEV_SPEC, subdev_spec_t());
+ ////////////////////////////////////////////////////////////////////
+ // do some post-init tasks
+ ////////////////////////////////////////////////////////////////////
+ //and now that the tick rate is set, init the host rates to something
+ BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){
+ _tree->access<double>(mb_path / "rx_dsps" / name / "rate" / "value").set(1e6);
+ }
+ BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){
+ _tree->access<double>(mb_path / "tx_dsps" / name / "rate" / "value").set(1e6);
+ }
- //initialize the send/recv
- io_init();
+ _tree->access<subdev_spec_t>(mb_path / "rx_subdev_spec").set(_rx_subdev_spec);
+ _tree->access<subdev_spec_t>(mb_path / "tx_subdev_spec").set(_tx_subdev_spec);
+
}
usrp1_impl::~usrp1_impl(void){UHD_SAFE_CALL(
@@ -212,42 +390,52 @@ usrp1_impl::~usrp1_impl(void){UHD_SAFE_CALL(
this->enable_tx(false);
)}
-bool usrp1_impl::recv_async_msg(uhd::async_metadata_t &, double timeout){
- //dummy fill-in for the recv_async_msg
- boost::this_thread::sleep(boost::posix_time::microseconds(long(timeout*1e6)));
- return false;
+/*!
+ * Capabilities Register
+ *
+ * 3 2 1 0
+ * 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0
+ * +-----------------------------------------------+-+-----+-+-----+
+ * | Reserved |T|DUCs |R|DDCs |
+ * +-----------------------------------------------+-+-----+-+-----+
+ */
+size_t usrp1_impl::get_num_ddcs(void){
+ boost::uint32_t regval = _iface->peek32(FR_RB_CAPS);
+ return (regval >> 0) & 0x0007;
}
-/***********************************************************************
- * Device Get
- **********************************************************************/
-void usrp1_impl::get(const wax::obj &key_, wax::obj &val)
-{
- named_prop_t key = named_prop_t::extract(key_);
-
- //handle the get request conditioned on the key
- switch(key.as<device_prop_t>()){
- case DEVICE_PROP_NAME:
- val = std::string("usrp1 device");
- return;
-
- case DEVICE_PROP_MBOARD:
- UHD_ASSERT_THROW(key.name == "");
- val = _mboard_proxy->get_link();
- return;
+size_t usrp1_impl::get_num_ducs(void){
+ boost::uint32_t regval = _iface->peek32(FR_RB_CAPS);
+ return (regval >> 4) & 0x0007;
+}
- case DEVICE_PROP_MBOARD_NAMES:
- val = prop_names_t(1, ""); //vector of size 1 with empty string
- return;
+bool usrp1_impl::has_rx_halfband(void){
+ boost::uint32_t regval = _iface->peek32(FR_RB_CAPS);
+ return (regval >> 3) & 0x0001;
+}
- default: UHD_THROW_PROP_GET_ERROR();
- }
+bool usrp1_impl::has_tx_halfband(void){
+ boost::uint32_t regval = _iface->peek32(FR_RB_CAPS);
+ return (regval >> 7) & 0x0001;
}
/***********************************************************************
- * Device Set
+ * Properties callback methods below
**********************************************************************/
-void usrp1_impl::set(const wax::obj &, const wax::obj &)
-{
- UHD_THROW_PROP_SET_ERROR();
+void usrp1_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){
+ mb_eeprom.commit(*_fx2_ctrl, mboard_eeprom_t::MAP_B000);
+}
+
+void usrp1_impl::set_db_eeprom(const std::string &db, const std::string &type, const uhd::usrp::dboard_eeprom_t &db_eeprom){
+ if (type == "rx") db_eeprom.store(*_fx2_ctrl, (db == "A")? (I2C_ADDR_RX_A) : (I2C_ADDR_RX_B));
+ if (type == "tx") db_eeprom.store(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A) : (I2C_ADDR_TX_B));
+ if (type == "gdb") db_eeprom.store(*_fx2_ctrl, (db == "A")? (I2C_ADDR_TX_A ^ 5) : (I2C_ADDR_TX_B ^ 5));
+}
+
+double usrp1_impl::update_rx_codec_gain(const std::string &db, const double gain){
+ //set gain on both I and Q, readback on one
+ //TODO in the future, gains should have individual control
+ _dbc[db].codec->set_rx_pga_gain(gain, 'A');
+ _dbc[db].codec->set_rx_pga_gain(gain, 'B');
+ return _dbc[db].codec->get_rx_pga_gain('A');
}
diff --git a/host/lib/usrp/usrp1/usrp1_impl.hpp b/host/lib/usrp/usrp1/usrp1_impl.hpp
index bea1dbe3b..f156d0bc4 100644
--- a/host/lib/usrp/usrp1/usrp1_impl.hpp
+++ b/host/lib/usrp/usrp1/usrp1_impl.hpp
@@ -16,16 +16,17 @@
//
#include "usrp1_iface.hpp"
-#include "clock_ctrl.hpp"
#include "codec_ctrl.hpp"
#include "soft_time_ctrl.hpp"
#include <uhd/device.hpp>
+#include <uhd/property_tree.hpp>
#include <uhd/utils/pimpl.hpp>
#include <uhd/types/dict.hpp>
#include <uhd/types/otw_type.hpp>
#include <uhd/types/clock_config.hpp>
#include <uhd/types/stream_cmd.hpp>
#include <uhd/usrp/dboard_id.hpp>
+#include <uhd/usrp/mboard_eeprom.hpp>
#include <uhd/usrp/subdev_spec.hpp>
#include <uhd/usrp/dboard_eeprom.hpp>
#include <uhd/usrp/dboard_manager.hpp>
@@ -35,29 +36,6 @@
#define INCLUDED_USRP1_IMPL_HPP
/*!
- * Simple wax obj proxy class:
- * Provides a wax obj interface for a set and a get function.
- * This allows us to create nested properties structures
- * while maintaining flattened code within the implementation.
- */
-class wax_obj_proxy : public wax::obj {
-public:
- typedef boost::function<void(const wax::obj &, wax::obj &)> get_t;
- typedef boost::function<void(const wax::obj &, const wax::obj &)> set_t;
- typedef boost::shared_ptr<wax_obj_proxy> sptr;
-
- static sptr make(const get_t &get, const set_t &set){
- return sptr(new wax_obj_proxy(get, set));
- }
-
-private:
- get_t _get; set_t _set;
- wax_obj_proxy(const get_t &get, const set_t &set): _get(get), _set(set) {};
- void get(const wax::obj &key, wax::obj &val) {return _get(key, val);}
- void set(const wax::obj &key, const wax::obj &val) {return _set(key, val);}
-};
-
-/*!
* USRP1 implementation guts:
* The implementation details are encapsulated here.
* Handles properties on the mboard, dboard, dsps...
@@ -73,9 +51,7 @@ public:
static const std::vector<dboard_slot_t> _dboard_slots;
//structors
- usrp1_impl(uhd::transport::usb_zero_copy::sptr data_transport,
- uhd::usrp::fx2_ctrl::sptr ctrl_transport);
-
+ usrp1_impl(const uhd::device_addr_t &);
~usrp1_impl(void);
//the io interface
@@ -97,31 +73,44 @@ public:
bool recv_async_msg(uhd::async_metadata_t &, double);
private:
- /*!
- * Make a usrp1 dboard interface.
- * \param iface the usrp1 interface object
- * \param clock the clock control interface
- * \param codec the codec control interface
- * \param dboard_slot the slot identifier
- * \param rx_dboard_id the db id for the rx board (used for evil dbsrx purposes)
- * \return a sptr to a new dboard interface
- */
- static uhd::usrp::dboard_iface::sptr make_dboard_iface(
- usrp1_iface::sptr iface,
- usrp1_clock_ctrl::sptr clock,
- usrp1_codec_ctrl::sptr codec,
- dboard_slot_t dboard_slot,
- const uhd::usrp::dboard_id_t &rx_dboard_id
- );
+ uhd::property_tree::sptr _tree;
- //!call when the channel mapping is changed
- void update_xport_channel_mapping(void);
+ //device properties interface
+ void get(const wax::obj &, wax::obj &val){
+ val = _tree; //entry point into property tree
+ }
- //soft time control emulation
+ //controllers
+ uhd::usrp::fx2_ctrl::sptr _fx2_ctrl;
+ usrp1_iface::sptr _iface;
uhd::usrp::soft_time_ctrl::sptr _soft_time_ctrl;
+ uhd::transport::usb_zero_copy::sptr _data_transport;
+ struct db_container_type{
+ usrp1_codec_ctrl::sptr codec;
+ uhd::usrp::dboard_iface::sptr dboard_iface;
+ uhd::usrp::dboard_manager::sptr dboard_manager;
+ };
+ uhd::dict<std::string, db_container_type> _dbc;
- //interface to ioctls and file descriptor
- usrp1_iface::sptr _iface;
+ double _master_clock_rate; //clock rate shadow
+
+ void set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &);
+ void set_db_eeprom(const std::string &, const std::string &, const uhd::usrp::dboard_eeprom_t &);
+ double update_rx_codec_gain(const std::string &, const double); //sets A and B at once
+ void update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &);
+ void update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &);
+ double update_rx_samp_rate(const double);
+ double update_tx_samp_rate(const double);
+ double update_rx_dsp_freq(const size_t, const double);
+ double update_tx_dsp_freq(const size_t, const double);
+
+ static uhd::usrp::dboard_iface::sptr make_dboard_iface(
+ usrp1_iface::sptr,
+ usrp1_codec_ctrl::sptr,
+ dboard_slot_t,
+ const double,
+ const uhd::usrp::dboard_id_t &
+ );
//handle io stuff
UHD_PIMPL_DECL(io_impl) _io_impl;
@@ -129,78 +118,10 @@ private:
void rx_stream_on_off(bool);
void handle_overrun(size_t);
- //underrun and overrun poll intervals
- size_t _rx_samps_per_poll_interval;
- size_t _tx_samps_per_poll_interval;
-
//otw types
- uhd::otw_type_t _rx_otw_type;
- uhd::otw_type_t _tx_otw_type;
-
- //configuration shadows
+ uhd::otw_type_t _rx_otw_type, _tx_otw_type;
uhd::usrp::subdev_spec_t _rx_subdev_spec, _tx_subdev_spec;
- //clock control
- usrp1_clock_ctrl::sptr _clock_ctrl;
-
- //ad9862 codec control interface
- uhd::dict<dboard_slot_t, usrp1_codec_ctrl::sptr> _codec_ctrls;
-
- //codec properties interfaces
- void codec_init(void);
- void rx_codec_get(const wax::obj &, wax::obj &, dboard_slot_t);
- void rx_codec_set(const wax::obj &, const wax::obj &, dboard_slot_t);
- void tx_codec_get(const wax::obj &, wax::obj &, dboard_slot_t);
- void tx_codec_set(const wax::obj &, const wax::obj &, dboard_slot_t);
- uhd::dict<dboard_slot_t, wax_obj_proxy::sptr> _rx_codec_proxies, _tx_codec_proxies;
-
- //device functions and settings
- void get(const wax::obj &, wax::obj &);
- void set(const wax::obj &, const wax::obj &);
-
- //mboard functions and settings
- void mboard_init(void);
- void mboard_get(const wax::obj &, wax::obj &);
- void mboard_set(const wax::obj &, const wax::obj &);
- wax_obj_proxy::sptr _mboard_proxy;
-
- //xx dboard functions and settings
- void dboard_init(void);
- uhd::dict<dboard_slot_t, uhd::usrp::dboard_manager::sptr> _dboard_managers;
- uhd::dict<dboard_slot_t, uhd::usrp::dboard_iface::sptr> _dboard_ifaces;
-
- //rx dboard functions and settings
- uhd::dict<dboard_slot_t, uhd::usrp::dboard_eeprom_t> _rx_db_eeproms;
- void rx_dboard_get(const wax::obj &, wax::obj &, dboard_slot_t);
- void rx_dboard_set(const wax::obj &, const wax::obj &, dboard_slot_t);
- uhd::dict<dboard_slot_t, wax_obj_proxy::sptr> _rx_dboard_proxies;
-
- //tx dboard functions and settings
- uhd::dict<dboard_slot_t, uhd::usrp::dboard_eeprom_t> _tx_db_eeproms, _gdb_eeproms;
- void tx_dboard_get(const wax::obj &, wax::obj &, dboard_slot_t);
- void tx_dboard_set(const wax::obj &, const wax::obj &, dboard_slot_t);
- uhd::dict<dboard_slot_t, wax_obj_proxy::sptr> _tx_dboard_proxies;
-
- //rx dsp functions and settings
- void rx_dsp_init(void);
- void rx_dsp_get(const wax::obj &, wax::obj &, size_t);
- void rx_dsp_set(const wax::obj &, const wax::obj &, size_t);
- uhd::dict<size_t, double> _rx_dsp_freqs;
- size_t _rx_dsp_decim;
- uhd::dict<std::string, wax_obj_proxy::sptr> _rx_dsp_proxies;
-
- //tx dsp functions and settings
- void tx_dsp_init(void);
- void tx_dsp_get(const wax::obj &, wax::obj &, size_t);
- void tx_dsp_set(const wax::obj &, const wax::obj &, size_t);
- uhd::dict<size_t, double> _tx_dsp_freqs;
- size_t _tx_dsp_interp;
- uhd::dict<std::string, wax_obj_proxy::sptr> _tx_dsp_proxies;
-
- //transports
- uhd::transport::usb_zero_copy::sptr _data_transport;
- uhd::usrp::fx2_ctrl::sptr _ctrl_transport;
-
//capabilities
size_t get_num_ducs(void);
size_t get_num_ddcs(void);
@@ -211,11 +132,11 @@ private:
bool _rx_enabled, _tx_enabled;
void enable_rx(bool enb){
_rx_enabled = enb;
- _ctrl_transport->usrp_rx_enable(enb);
+ _fx2_ctrl->usrp_rx_enable(enb);
}
void enable_tx(bool enb){
_tx_enabled = enb;
- _ctrl_transport->usrp_tx_enable(enb);
+ _fx2_ctrl->usrp_tx_enable(enb);
}
//conditionally disable and enable rx