aboutsummaryrefslogtreecommitdiffstats
path: root/mpm
diff options
context:
space:
mode:
authorMark Meserve <mark.meserve@ni.com>2017-04-10 15:36:35 -0700
committerMartin Braun <martin.braun@ettus.com>2017-12-22 15:03:45 -0800
commit701904882cb63202f277af18c7ef11ac6cc3a581 (patch)
tree910db7bcb7129a7c1d5f8d883fe21b37ff91ebe2 /mpm
parentae21f9b9d38cb98c91bee84fc4fcf6a81a3e0c0c (diff)
downloaduhd-701904882cb63202f277af18c7ef11ac6cc3a581.tar.gz
uhd-701904882cb63202f277af18c7ef11ac6cc3a581.tar.bz2
uhd-701904882cb63202f277af18c7ef11ac6cc3a581.zip
mpm: Improved ad937x code
- Add gain control pin configuration - Fixed gcc compilation - Better docstrings
Diffstat (limited to 'mpm')
-rw-r--r--mpm/dboards/magnesium_manager.cpp2
-rw-r--r--mpm/include/mpm/ad937x/ad937x_ctrl.hpp92
-rw-r--r--mpm/include/mpm/ad937x/ad937x_ctrl_types.hpp59
-rw-r--r--mpm/lib/mykonos/ad937x_ctrl.cpp75
-rw-r--r--mpm/lib/mykonos/ad937x_device.cpp176
-rw-r--r--mpm/lib/mykonos/ad937x_device.hpp49
-rw-r--r--mpm/lib/mykonos/ad937x_device_types.hpp46
-rw-r--r--mpm/lib/mykonos/config/CMakeLists.txt1
-rw-r--r--mpm/lib/mykonos/config/ad937x_gain_ctrl_config.cpp141
-rw-r--r--mpm/lib/mykonos/config/ad937x_gain_ctrl_config.hpp72
10 files changed, 632 insertions, 81 deletions
diff --git a/mpm/dboards/magnesium_manager.cpp b/mpm/dboards/magnesium_manager.cpp
index d5e07d1e0..8639a7ff1 100644
--- a/mpm/dboards/magnesium_manager.cpp
+++ b/mpm/dboards/magnesium_manager.cpp
@@ -28,5 +28,5 @@ magnesium_periph_manager::magnesium_periph_manager(
_clock_spi = lmk04828_spi_iface::make(mpm::spi::spidev_iface::make(lmk_spidev));
_clock_ctrl = lmk04828_iface::make(_clock_spi->get_write_fn(), _clock_spi->get_read_fn());
_mykonos_spi = mpm::spi::spidev_iface::make(mykonos_spidev);
- _mykonos_ctrl = ad937x_ctrl::make(_spi_mutex, _mykonos_spi);
+ _mykonos_ctrl = ad937x_ctrl::make(_spi_mutex, _mykonos_spi, mpm::ad937x::gpio::gain_pins_t());
};
diff --git a/mpm/include/mpm/ad937x/ad937x_ctrl.hpp b/mpm/include/mpm/ad937x/ad937x_ctrl.hpp
index aeb550f00..04332393e 100644
--- a/mpm/include/mpm/ad937x/ad937x_ctrl.hpp
+++ b/mpm/include/mpm/ad937x/ad937x_ctrl.hpp
@@ -17,6 +17,8 @@
#pragma once
+#include "ad937x_ctrl_types.hpp"
+
#include <uhd/types/direction.hpp>
#include <uhd/types/ranges.hpp>
#include <uhd/exception.hpp>
@@ -28,38 +30,126 @@
#include <set>
#include <mutex>
+/*! AD937x Control Interface
+*
+* A sane API for configuring AD937x chips.
+*
+* \section ad937x_which The `which` parameter
+*
+* Many function calls require a `which` string parameter to select
+* the RF frontend. Valid values for `which` are:
+* - RX1, RX2
+* - TX1, TX2
+*
+* Frontend numbering is as designed by the AD9371.
+*
+* While all functions that use `which` specify an individual channel,
+* certain functions affect more than one channel due to the limitations of
+* the AD9371.
+*/
class ad937x_ctrl : public boost::noncopyable
{
public:
typedef std::shared_ptr<ad937x_ctrl> sptr;
- static sptr make(std::shared_ptr<std::mutex> spi_mutex, uhd::spi_iface::sptr iface);
+ /*! \brief make a new AD9371 ctrl object using the specified SPI iface
+ *
+ * \param spi_mutex a mutex that will be locked whenever the SPI iface is to be used
+ * \param iface the spi_iface for accessing the AD9371
+ */
+ static sptr make(
+ std::shared_ptr<std::mutex> spi_mutex,
+ uhd::spi_iface::sptr iface,
+ mpm::ad937x::gpio::gain_pins_t gain_pins);
virtual ~ad937x_ctrl(void) {}
+ //! get the RF frequency range for the AD9371
static uhd::meta_range_t get_rf_freq_range(void);
+
+ //! get the BW filter range for the AD9371
static uhd::meta_range_t get_bw_filter_range(void);
+
+ //! get valid clock rates for the AD9371
static std::vector<double> get_clock_rates(void);
+
+ //! get the gain range for a frontend (RX, TX)
static uhd::meta_range_t get_gain_range(const std::string &which);
+ //! read the product ID from the device
virtual uint8_t get_product_id() = 0;
+
+ //! read the product revision from the device
virtual uint8_t get_device_rev() = 0;
+
+ /*! \brief get the API version from the software driver
+ *
+ * \return a version string in the format "SILICON.MAJOR.MINOR.BUILD"
+ */
virtual std::string get_api_version() = 0;
+
+ /*! \brief get the currently loaded ARM version from the device
+ *
+ * \return a version string in the format "MAJOR.MINOR.RC"
+ */
virtual std::string get_arm_version() = 0;
+ //! set the BW filter for the frontend which
virtual double set_bw_filter(const std::string &which, double value) = 0;
+
+ /*! \brief set the gain for the frontend which
+ *
+ * \param which frontend string
+ * \param value target gain value
+ * \return actual gain value
+ */
virtual double set_gain(const std::string &which, double value) = 0;
+ /*! \brief set the agc mode for all RX channels
+ *
+ * \param which frontend string
+ * \param mode requested mode (automatic, manual, hybrid)
+ */
virtual void set_agc_mode(const std::string &which, const std::string &mode) = 0;
+ /*! \brief set the clock rate for the device
+ *
+ * \param value requested clock rate
+ * \return actual clock rate
+ */
virtual double set_clock_rate(double value) = 0;
+
+ //! enable the frontend which
virtual void enable_channel(const std::string &which, bool enable) = 0;
+ /*! \brief set the RF frequency for the direction specified in which
+ * Sets the RF frequency. This is a per direction setting.
+ * \param which frontend string to specify direction to tune
+ * \param value target frequency
+ * \return actual frequency
+ */
virtual double set_freq(const std::string &which, double value) = 0;
+
+ /*! \brief get the RF frequency for the direction specified in which
+ /* Gets the RF frequency. This is a per direction setting.
+ * \param which frontend string to specify direction to get
+ * \return actual frequency
+ */
virtual double get_freq(const std::string &which) = 0;
+ //! set the FIR filter for the frontend which
virtual void set_fir(const std::string &which, int8_t gain, const std::vector<int16_t> & fir) = 0;
+
+ //! get the FIR filter for the frontend which
virtual std::vector<int16_t> get_fir(const std::string &which, int8_t &gain) = 0;
+ // TODO: update docstring with temperature unit and calibration information
+ //! get the device temperature
virtual int16_t get_temperature() = 0;
+
+ //! enable or disable gain ctrl pins for one channel
+ virtual void set_enable_gain_pins(const std::string &which, bool enable) = 0;
+
+ //! set step sizes for gain ctrl pins for one channel
+ virtual void set_gain_pin_step_sizes(const std::string &which, double inc_step, double dec_step) = 0;
};
#ifdef LIBMPM_PYTHON
diff --git a/mpm/include/mpm/ad937x/ad937x_ctrl_types.hpp b/mpm/include/mpm/ad937x/ad937x_ctrl_types.hpp
new file mode 100644
index 000000000..003e2e3af
--- /dev/null
+++ b/mpm/include/mpm/ad937x/ad937x_ctrl_types.hpp
@@ -0,0 +1,59 @@
+//
+// Copyright 2017 Ettus Research (National Instruments)
+//
+// 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/>.
+//
+
+#pragma once
+
+namespace mpm {
+ namespace ad937x {
+ namespace gpio {
+ enum class gain_pin_t {
+ NONE,
+ PIN0,
+ PIN1,
+ PIN2,
+ PIN3,
+ PIN4,
+ PIN5,
+ PIN6,
+ PIN7,
+ PIN8,
+ PIN9,
+ PIN10,
+ PIN11,
+ PIN12,
+ PIN13,
+ PIN14,
+ PIN15,
+ PIN16,
+ PIN17,
+ PIN18,
+ };
+
+ struct gain_pins_t
+ {
+ gain_pin_t rx1_inc_gain_pin;
+ gain_pin_t rx1_dec_gain_pin;
+ gain_pin_t rx2_inc_gain_pin;
+ gain_pin_t rx2_dec_gain_pin;
+ gain_pin_t tx1_inc_gain_pin;
+ gain_pin_t tx1_dec_gain_pin;
+ gain_pin_t tx2_inc_gain_pin;
+ gain_pin_t tx2_dec_gain_pin;
+ };
+ }
+ }
+} \ No newline at end of file
diff --git a/mpm/lib/mykonos/ad937x_ctrl.cpp b/mpm/lib/mykonos/ad937x_ctrl.cpp
index ce98706fa..cef729686 100644
--- a/mpm/lib/mykonos/ad937x_ctrl.cpp
+++ b/mpm/lib/mykonos/ad937x_ctrl.cpp
@@ -17,13 +17,14 @@
#include "ad937x_device.hpp"
#include "adi/mykonos.h"
-
-#include <mpm/ad937x/ad937x_ctrl.hpp>
+#include "mpm/ad937x/ad937x_ctrl.hpp"
#include <sstream>
#include <set>
#include <functional>
+using namespace mpm::ad937x::device;
+
static uhd::direction_t _get_direction_from_antenna(const std::string& antenna)
{
auto sub = antenna.substr(0, 2);
@@ -39,19 +40,19 @@ static uhd::direction_t _get_direction_from_antenna(const std::string& antenna)
return uhd::direction_t::RX_DIRECTION;
}
-static ad937x_device::chain_t _get_chain_from_antenna(const std::string& antenna)
+static chain_t _get_chain_from_antenna(const std::string& antenna)
{
auto sub = antenna.substr(2, 1);
if (sub == "1") {
- return ad937x_device::chain_t::ONE;
+ return chain_t::ONE;
}
else if (sub == "2") {
- return ad937x_device::chain_t::TWO;
+ return chain_t::TWO;
}
else {
throw uhd::runtime_error("ad937x_ctrl got an invalid channel string.");
}
- return ad937x_device::chain_t::ONE;
+ return chain_t::ONE;
}
std::set<size_t> _get_valid_fir_lengths(const std::string& which)
@@ -69,6 +70,18 @@ std::set<size_t> _get_valid_fir_lengths(const std::string& which)
}
}
+uhd::meta_range_t _get_valid_rx_gain_steps()
+{
+ // 0-7 step size is valid, in 0.5 dB increments
+ return uhd::meta_range_t(0, 3.5, 0.5);
+}
+
+uhd::meta_range_t _get_valid_tx_gain_steps()
+{
+ // 0-31 step size is valid, in 0.05 dB increments
+ return uhd::meta_range_t(0, 1.55, 0.05);
+}
+
uhd::meta_range_t ad937x_ctrl::get_rf_freq_range(void)
{
return uhd::meta_range_t(ad937x_device::MIN_FREQ, ad937x_device::MAX_FREQ);
@@ -105,9 +118,12 @@ uhd::meta_range_t ad937x_ctrl::get_gain_range(const std::string &which)
class ad937x_ctrl_impl : public ad937x_ctrl
{
public:
- ad937x_ctrl_impl(std::shared_ptr<std::mutex> spi_mutex, uhd::spi_iface::sptr iface) :
+ ad937x_ctrl_impl(
+ std::shared_ptr<std::mutex> spi_mutex,
+ uhd::spi_iface::sptr iface,
+ mpm::ad937x::gpio::gain_pins_t gain_pins) :
spi_mutex(spi_mutex),
- device(iface)
+ device(iface, gain_pins)
{
}
@@ -161,6 +177,8 @@ public:
return device.set_gain(dir, chain, value);
}
+ // TODO: does agc mode need to have a which parameter?
+ // this affects all RX channels on the device
virtual void set_agc_mode(const std::string &which, const std::string &mode)
{
auto dir = _get_direction_from_antenna(which);
@@ -256,14 +274,51 @@ public:
return device.get_temperature();
}
+ virtual void set_enable_gain_pins(const std::string &which, bool enable)
+ {
+ auto dir = _get_direction_from_antenna(which);
+ auto chain = _get_chain_from_antenna(which);
+
+ std::lock_guard<std::mutex> lock(*spi_mutex);
+ device.set_enable_gain_pins(dir, chain, enable);
+ }
+
+ virtual void set_gain_pin_step_sizes(const std::string &which, double inc_step, double dec_step)
+ {
+ auto dir = _get_direction_from_antenna(which);
+ auto chain = _get_chain_from_antenna(which);
+
+ if (dir == uhd::RX_DIRECTION)
+ {
+ auto steps = _get_valid_rx_gain_steps();
+ inc_step = steps.clip(inc_step);
+ dec_step = steps.clip(dec_step);
+ }
+ else if (dir == uhd::TX_DIRECTION)
+ {
+ auto steps = _get_valid_tx_gain_steps();
+ inc_step = steps.clip(inc_step);
+ dec_step = steps.clip(dec_step);
+
+ // double comparison here should be okay because of clipping
+ if (inc_step != dec_step)
+ {
+ throw uhd::value_error("TX gain increment and decrement steps must be equal");
+ }
+ }
+
+ std::lock_guard<std::mutex> lock(*spi_mutex);
+ device.set_gain_pin_step_sizes(dir, chain, inc_step, dec_step);
+ }
+
private:
ad937x_device device;
std::shared_ptr<std::mutex> spi_mutex;
};
-ad937x_ctrl::sptr ad937x_ctrl::make(std::shared_ptr<std::mutex> spi_mutex, uhd::spi_iface::sptr iface)
+ad937x_ctrl::sptr ad937x_ctrl::make(std::shared_ptr<std::mutex> spi_mutex, uhd::spi_iface::sptr iface, mpm::ad937x::gpio::gain_pins_t gain_pins)
{
- return std::make_shared<ad937x_ctrl_impl>(spi_mutex, iface);
+ return std::make_shared<ad937x_ctrl_impl>(spi_mutex, iface, gain_pins);
}
diff --git a/mpm/lib/mykonos/ad937x_device.cpp b/mpm/lib/mykonos/ad937x_device.cpp
index 85eb9553a..2eb1db60a 100644
--- a/mpm/lib/mykonos/ad937x_device.cpp
+++ b/mpm/lib/mykonos/ad937x_device.cpp
@@ -22,6 +22,10 @@
#include <functional>
#include <iostream>
+using namespace mpm::ad937x::device;
+using namespace mpm::ad937x::gpio;
+using namespace uhd;
+
const double ad937x_device::MIN_FREQ = 300e6;
const double ad937x_device::MAX_FREQ = 6e9;
const double ad937x_device::MIN_RX_GAIN = 0.0;
@@ -109,42 +113,45 @@ void ad937x_device::_call_gpio_api_function(std::function<mykonosGpioErr_t()> fu
void ad937x_device::_initialize()
{
+ // TODO: make this reset actually do something (implement CMB_HardReset or replace)
_call_api_function(std::bind(MYKONOS_resetDevice, mykonos_config.device));
if (get_product_id() != AD9371_PRODUCT_ID)
{
- throw uhd::runtime_error("AD9371 product ID does not match expected ID!");
+ throw runtime_error("AD9371 product ID does not match expected ID!");
}
_call_api_function(std::bind(MYKONOS_initialize, mykonos_config.device));
if (!get_pll_lock_status(pll_t::CLK_SYNTH))
{
- throw uhd::runtime_error("AD937x CLK_SYNTH PLL failed to lock in initialize()");
+ throw runtime_error("AD937x CLK_SYNTH PLL failed to lock in initialize()");
}
std::vector<uint8_t> binary(98304, 0);
_load_arm(binary);
- tune(uhd::RX_DIRECTION, RX_DEFAULT_FREQ);
- tune(uhd::TX_DIRECTION, TX_DEFAULT_FREQ);
+ // TODO: Add multi-chip sync code
+
+ tune(RX_DIRECTION, RX_DEFAULT_FREQ);
+ tune(TX_DIRECTION, TX_DEFAULT_FREQ);
// TODO: wait 200ms or change to polling
if (!get_pll_lock_status(pll_t::RX_SYNTH))
{
- throw uhd::runtime_error("AD937x RX PLL failed to lock in initialize()");
+ throw runtime_error("AD937x RX PLL failed to lock in initialize()");
}
if (!get_pll_lock_status(pll_t::TX_SYNTH))
{
- throw uhd::runtime_error("AD937x TX PLL failed to lock in initialize()");
+ throw runtime_error("AD937x TX PLL failed to lock in initialize()");
}
// TODO: ADD GPIO CTRL setup here
- set_gain(uhd::RX_DIRECTION, chain_t::ONE, 0);
- set_gain(uhd::RX_DIRECTION, chain_t::TWO, 0);
- set_gain(uhd::TX_DIRECTION, chain_t::ONE, 0);
- set_gain(uhd::TX_DIRECTION, chain_t::TWO, 0);
+ set_gain(RX_DIRECTION, chain_t::ONE, 0);
+ set_gain(RX_DIRECTION, chain_t::TWO, 0);
+ set_gain(TX_DIRECTION, chain_t::ONE, 0);
+ set_gain(TX_DIRECTION, chain_t::TWO, 0);
_run_initialization_calibrations();
@@ -160,6 +167,11 @@ void ad937x_device::_initialize()
// TODO: ordering of this doesn't seem right, intuitively, verify this works
_call_api_function(std::bind(MYKONOS_setObsRxPathSource, mykonos_config.device, OBS_RXOFF));
_call_api_function(std::bind(MYKONOS_setObsRxPathSource, mykonos_config.device, OBS_INTERNALCALS));
+
+ _apply_gain_pins(RX_DIRECTION, chain_t::ONE);
+ _apply_gain_pins(RX_DIRECTION, chain_t::TWO);
+ _apply_gain_pins(TX_DIRECTION, chain_t::ONE);
+ _apply_gain_pins(TX_DIRECTION, chain_t::TWO);
}
// TODO: review const-ness in this function with respect to ADI API
@@ -169,7 +181,7 @@ void ad937x_device::_load_arm(std::vector<uint8_t> & binary)
if (binary.size() == ARM_BINARY_SIZE)
{
- throw uhd::runtime_error("ad937x_device ARM is not the correct size!");
+ throw runtime_error("ad937x_device ARM is not the correct size!");
}
_call_api_function(std::bind(MYKONOS_loadArmFromBinary, mykonos_config.device, &binary[0], binary.size()));
@@ -241,9 +253,10 @@ void ad937x_device::_enable_tracking_calibrations()
_call_api_function(std::bind(MYKONOS_enableTrackingCals, mykonos_config.device, TRACKING_CALS));
}
-ad937x_device::ad937x_device(uhd::spi_iface::sptr iface) :
+ad937x_device::ad937x_device(spi_iface::sptr iface, gain_pins_t gain_pins) :
full_spi_settings(iface),
- mykonos_config(&full_spi_settings.spi_settings)
+ mykonos_config(&full_spi_settings.spi_settings),
+ gain_ctrl(gain_pins)
{
_initialize();
}
@@ -262,7 +275,7 @@ uint8_t ad937x_device::get_device_rev()
return rev;
}
-ad937x_device::api_version_t ad937x_device::get_api_version()
+api_version_t ad937x_device::get_api_version()
{
api_version_t api;
_call_api_function(std::bind(MYKONOS_getApiVersion,
@@ -274,7 +287,7 @@ ad937x_device::api_version_t ad937x_device::get_api_version()
return api;
}
-ad937x_device::arm_version_t ad937x_device::get_arm_version()
+arm_version_t ad937x_device::get_arm_version()
{
arm_version_t arm;
_call_api_function(std::bind(MYKONOS_getArmVersion,
@@ -293,14 +306,14 @@ double ad937x_device::set_clock_rate(double req_rate)
return static_cast<double>(rate);
}
-void ad937x_device::enable_channel(uhd::direction_t direction, chain_t chain, bool enable)
+void ad937x_device::enable_channel(direction_t direction, chain_t chain, bool enable)
{
// TODO:
// Turns out the only code in the API that actually sets the channel enable settings
- // _initialize(). Need to figure out how to deal with this.
+ // is _initialize(). Need to figure out how to deal with this.
}
-double ad937x_device::tune(uhd::direction_t direction, double value)
+double ad937x_device::tune(direction_t direction, double value)
{
// I'm not sure why we set the PLL value in the config AND as a function parameter
// but here it is
@@ -309,11 +322,11 @@ double ad937x_device::tune(uhd::direction_t direction, double value)
uint64_t integer_value = static_cast<uint64_t>(value);
switch (direction)
{
- case uhd::TX_DIRECTION:
+ case TX_DIRECTION:
pll = TX_PLL;
mykonos_config.device->tx->txPllLoFrequency_Hz = integer_value;
break;
- case uhd::RX_DIRECTION:
+ case RX_DIRECTION:
pll = RX_PLL;
mykonos_config.device->rx->rxPllLoFrequency_Hz = integer_value;
break;
@@ -330,13 +343,13 @@ double ad937x_device::tune(uhd::direction_t direction, double value)
return static_cast<double>(coerced_pll);
}
-double ad937x_device::get_freq(uhd::direction_t direction)
+double ad937x_device::get_freq(direction_t direction)
{
mykonosRfPllName_t pll;
switch (direction)
{
- case uhd::TX_DIRECTION: pll = TX_PLL; break;
- case uhd::RX_DIRECTION: pll = RX_PLL; break;
+ case TX_DIRECTION: pll = TX_PLL; break;
+ case RX_DIRECTION: pll = RX_PLL; break;
default:
UHD_THROW_INVALID_CODE_PATH();
}
@@ -355,22 +368,22 @@ bool ad937x_device::get_pll_lock_status(pll_t pll)
switch (pll)
{
case pll_t::CLK_SYNTH:
- return (pll_status & 0x01) ? 1 : 0;
+ return (pll_status & 0x01) > 0;
case pll_t::RX_SYNTH:
- return (pll_status & 0x02) ? 1 : 0;
+ return (pll_status & 0x02) > 0;
case pll_t::TX_SYNTH:
- return (pll_status & 0x04) ? 1 : 0;
+ return (pll_status & 0x04) > 0;
case pll_t::SNIFF_SYNTH:
- return (pll_status & 0x08) ? 1 : 0;
+ return (pll_status & 0x08) > 0;
case pll_t::CALPLL_SDM:
- return (pll_status & 0x10) ? 1 : 0;
+ return (pll_status & 0x10) > 0;
default:
UHD_THROW_INVALID_CODE_PATH();
return false;
}
}
-double ad937x_device::set_bw_filter(uhd::direction_t direction, chain_t chain, double value)
+double ad937x_device::set_bw_filter(direction_t direction, chain_t chain, double value)
{
// TODO: implement
return double();
@@ -395,12 +408,12 @@ uint16_t ad937x_device::_convert_tx_gain(double gain)
}
-double ad937x_device::set_gain(uhd::direction_t direction, chain_t chain, double value)
+double ad937x_device::set_gain(direction_t direction, chain_t chain, double value)
{
double coerced_value;
switch (direction)
{
- case uhd::TX_DIRECTION:
+ case TX_DIRECTION:
{
uint16_t attenuation = _convert_tx_gain(value);
coerced_value = static_cast<double>(attenuation);
@@ -420,7 +433,7 @@ double ad937x_device::set_gain(uhd::direction_t direction, chain_t chain, double
_call_api_function(std::bind(func, mykonos_config.device, attenuation));
break;
}
- case uhd::RX_DIRECTION:
+ case RX_DIRECTION:
{
uint8_t gain = _convert_rx_gain(value);
coerced_value = static_cast<double>(gain);
@@ -446,11 +459,11 @@ double ad937x_device::set_gain(uhd::direction_t direction, chain_t chain, double
return coerced_value;
}
-void ad937x_device::set_agc_mode(uhd::direction_t direction, gain_mode_t mode)
+void ad937x_device::set_agc_mode(direction_t direction, gain_mode_t mode)
{
switch (direction)
{
- case uhd::RX_DIRECTION:
+ case RX_DIRECTION:
switch (mode)
{
case gain_mode_t::MANUAL:
@@ -471,17 +484,17 @@ void ad937x_device::set_agc_mode(uhd::direction_t direction, gain_mode_t mode)
}
void ad937x_device::set_fir(
- const uhd::direction_t direction,
+ const direction_t direction,
const chain_t chain,
int8_t gain,
const std::vector<int16_t> & fir)
{
switch (direction)
{
- case uhd::TX_DIRECTION:
+ case TX_DIRECTION:
mykonos_config.tx_fir_config.set_fir(gain, fir);
break;
- case uhd::RX_DIRECTION:
+ case RX_DIRECTION:
mykonos_config.rx_fir_config.set_fir(gain, fir);
break;
default:
@@ -490,15 +503,15 @@ void ad937x_device::set_fir(
}
std::vector<int16_t> ad937x_device::get_fir(
- const uhd::direction_t direction,
+ const direction_t direction,
const chain_t chain,
int8_t &gain)
{
switch (direction)
{
- case uhd::TX_DIRECTION:
+ case TX_DIRECTION:
return mykonos_config.tx_fir_config.get_fir(gain);
- case uhd::RX_DIRECTION:
+ case RX_DIRECTION:
return mykonos_config.rx_fir_config.get_fir(gain);
default:
UHD_THROW_INVALID_CODE_PATH();
@@ -513,3 +526,86 @@ int16_t ad937x_device::get_temperature()
return status.tempCode;
}
+void ad937x_device::set_enable_gain_pins(direction_t direction, chain_t chain, bool enable)
+{
+ gain_ctrl.config.at(direction).at(chain).enable = enable;
+ _apply_gain_pins(direction, chain);
+}
+
+void ad937x_device::set_gain_pin_step_sizes(direction_t direction, chain_t chain, double inc_step, double dec_step)
+{
+ if (direction == RX_DIRECTION)
+ {
+ gain_ctrl.config.at(direction).at(chain).inc_step = static_cast<uint8_t>(inc_step / 0.5);
+ gain_ctrl.config.at(direction).at(chain).dec_step = static_cast<uint8_t>(dec_step / 0.5);
+ } else if (direction == TX_DIRECTION) {
+ // !!! TX is attenuation direction, so the pins are flipped !!!
+ gain_ctrl.config.at(direction).at(chain).dec_step = static_cast<uint8_t>(inc_step / 0.05);
+ gain_ctrl.config.at(direction).at(chain).inc_step = static_cast<uint8_t>(dec_step / 0.05);
+ } else {
+ UHD_THROW_INVALID_CODE_PATH();
+ }
+ _apply_gain_pins(direction, chain);
+}
+
+void ad937x_device::_apply_gain_pins(direction_t direction, chain_t chain)
+{
+ using namespace std::placeholders;
+
+ // get this channels configuration
+ auto chan = gain_ctrl.config.at(direction).at(chain);
+
+ // TX direction does not support different steps per direction
+ if (direction == TX_DIRECTION)
+ {
+ UHD_ASSERT_THROW(chan.inc_step == chan.dec_step);
+ }
+
+ switch (direction)
+ {
+ case RX_DIRECTION:
+ {
+ std::function<decltype(MYKONOS_setRx1GainCtrlPin)> func;
+ switch (chain)
+ {
+ case chain_t::ONE:
+ func = MYKONOS_setRx1GainCtrlPin;
+ break;
+ case chain_t::TWO:
+ func = MYKONOS_setRx2GainCtrlPin;
+ break;
+ }
+ _call_gpio_api_function(
+ std::bind(func,
+ mykonos_config.device,
+ chan.inc_step,
+ chan.dec_step,
+ chan.inc_pin,
+ chan.dec_pin,
+ chan.enable));
+ }
+ case TX_DIRECTION:
+ {
+ // TX sets attenuation, but the configuration should be stored correctly
+ std::function<decltype(MYKONOS_setTx2AttenCtrlPin)> func;
+ switch (chain)
+ {
+ case chain_t::ONE:
+ // TX1 has an extra parameter "useTx1ForTx2" that we do not support
+ func = std::bind(MYKONOS_setTx1AttenCtrlPin, _1, _2, _3, _4, _5, 0);
+ break;
+ case chain_t::TWO:
+ func = MYKONOS_setTx2AttenCtrlPin;
+ break;
+ }
+ _call_gpio_api_function(
+ std::bind(func,
+ mykonos_config.device,
+ chan.inc_step,
+ chan.inc_pin,
+ chan.dec_pin,
+ chan.enable));
+ }
+ }
+}
+
diff --git a/mpm/lib/mykonos/ad937x_device.hpp b/mpm/lib/mykonos/ad937x_device.hpp
index 59872b073..ccc696714 100644
--- a/mpm/lib/mykonos/ad937x_device.hpp
+++ b/mpm/lib/mykonos/ad937x_device.hpp
@@ -19,62 +19,50 @@
#include "config/ad937x_config_t.hpp"
#include "config/ad937x_fir.hpp"
+#include "config/ad937x_gain_ctrl_config.hpp"
+#include "mpm/ad937x/adi_ctrl.hpp"
+#include "ad937x_device_types.hpp"
+#include "mpm/ad937x/ad937x_ctrl_types.hpp"
#include "adi/t_mykonos.h"
#include "adi/t_mykonos_gpio.h"
-#include "mpm/ad937x/adi_ctrl.hpp"
-#include <uhd/types/direction.hpp>
-#include <uhd/types/ranges.hpp>
#include <uhd/exception.hpp>
#include <boost/noncopyable.hpp>
-#include <mutex>
#include <memory>
#include <functional>
class ad937x_device : public boost::noncopyable
{
public:
- struct api_version_t {
- uint32_t silicon_ver;
- uint32_t major_ver;
- uint32_t minor_ver;
- uint32_t build_ver;
- };
-
- struct arm_version_t {
- uint8_t major_ver;
- uint8_t minor_ver;
- uint8_t rc_ver;
- };
-
enum class gain_mode_t { MANUAL, AUTOMATIC, HYBRID };
- enum class chain_t { ONE, TWO };
enum class pll_t {CLK_SYNTH, RX_SYNTH, TX_SYNTH, SNIFF_SYNTH, CALPLL_SDM};
- typedef std::shared_ptr<ad937x_device> sptr;
- ad937x_device(uhd::spi_iface::sptr iface);
+ ad937x_device(uhd::spi_iface::sptr iface, mpm::ad937x::gpio::gain_pins_t gain_pins);
uint8_t get_product_id();
uint8_t get_device_rev();
- api_version_t get_api_version();
- arm_version_t get_arm_version();
+ mpm::ad937x::device::api_version_t get_api_version();
+ mpm::ad937x::device::arm_version_t get_arm_version();
- double set_bw_filter(uhd::direction_t direction, chain_t chain, double value);
- double set_gain(uhd::direction_t direction, chain_t chain, double value);
+ double set_bw_filter(uhd::direction_t direction, mpm::ad937x::device::chain_t chain, double value);
+ double set_gain(uhd::direction_t direction, mpm::ad937x::device::chain_t chain, double value);
void set_agc_mode(uhd::direction_t direction, gain_mode_t mode);
double set_clock_rate(double value);
- void enable_channel(uhd::direction_t direction, chain_t chain, bool enable);
+ void enable_channel(uhd::direction_t direction, mpm::ad937x::device::chain_t chain, bool enable);
double tune(uhd::direction_t direction, double value);
double get_freq(uhd::direction_t direction);
bool get_pll_lock_status(pll_t pll);
- void set_fir(uhd::direction_t direction, chain_t chain, int8_t gain, const std::vector<int16_t> & fir);
- std::vector<int16_t> get_fir(uhd::direction_t direction, chain_t chain, int8_t &gain);
+ void set_fir(uhd::direction_t direction, mpm::ad937x::device::chain_t chain, int8_t gain, const std::vector<int16_t> & fir);
+ std::vector<int16_t> get_fir(uhd::direction_t direction, mpm::ad937x::device::chain_t chain, int8_t &gain);
int16_t get_temperature();
+ void set_enable_gain_pins(uhd::direction_t direction, mpm::ad937x::device::chain_t chain, bool enable);
+ void set_gain_pin_step_sizes(uhd::direction_t direction, mpm::ad937x::device::chain_t chain, double inc_step, double dec_step);
+
const static double MIN_FREQ;
const static double MAX_FREQ;
const static double MIN_RX_GAIN;
@@ -85,14 +73,17 @@ public:
const static double TX_GAIN_STEP;
private:
+ ad9371_spiSettings_t full_spi_settings;
+ ad937x_config_t mykonos_config;
+ ad937x_gain_ctrl_config_t gain_ctrl;
+
void _initialize();
void _load_arm(std::vector<uint8_t> & binary);
void _run_initialization_calibrations();
void _start_jesd();
void _enable_tracking_calibrations();
- ad9371_spiSettings_t full_spi_settings;
- ad937x_config_t mykonos_config;
+ void _apply_gain_pins(uhd::direction_t direction, mpm::ad937x::device::chain_t chain);
void _call_api_function(std::function<mykonosErr_t()> func);
void _call_gpio_api_function(std::function<mykonosGpioErr_t()> func);
diff --git a/mpm/lib/mykonos/ad937x_device_types.hpp b/mpm/lib/mykonos/ad937x_device_types.hpp
new file mode 100644
index 000000000..cdc46fb5c
--- /dev/null
+++ b/mpm/lib/mykonos/ad937x_device_types.hpp
@@ -0,0 +1,46 @@
+//
+// Copyright 2017 Ettus Research (National Instruments)
+//
+// 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/>.
+//
+
+#pragma once
+
+// Include this to get all types for ad937x_device functions
+
+#include <uhd/types/direction.hpp>
+#include <uhd/types/ranges.hpp>
+
+namespace mpm {
+ namespace ad937x {
+ namespace device {
+
+ struct api_version_t {
+ uint32_t silicon_ver;
+ uint32_t major_ver;
+ uint32_t minor_ver;
+ uint32_t build_ver;
+ };
+
+ struct arm_version_t {
+ uint8_t major_ver;
+ uint8_t minor_ver;
+ uint8_t rc_ver;
+ };
+
+ enum class chain_t { ONE, TWO };
+ }
+ }
+}
+
diff --git a/mpm/lib/mykonos/config/CMakeLists.txt b/mpm/lib/mykonos/config/CMakeLists.txt
index dc52f2853..708963785 100644
--- a/mpm/lib/mykonos/config/CMakeLists.txt
+++ b/mpm/lib/mykonos/config/CMakeLists.txt
@@ -1,4 +1,5 @@
MYKONOS_APPEND_SOURCES(
${CMAKE_CURRENT_SOURCE_DIR}/ad937x_fir.cpp
${CMAKE_CURRENT_SOURCE_DIR}/ad937x_config_t.cpp
+ ${CMAKE_CURRENT_SOURCE_DIR}/ad937x_gain_ctrl_config.cpp
)
diff --git a/mpm/lib/mykonos/config/ad937x_gain_ctrl_config.cpp b/mpm/lib/mykonos/config/ad937x_gain_ctrl_config.cpp
new file mode 100644
index 000000000..f52982a96
--- /dev/null
+++ b/mpm/lib/mykonos/config/ad937x_gain_ctrl_config.cpp
@@ -0,0 +1,141 @@
+//
+// Copyright 2017 Ettus Research (National Instruments)
+//
+// 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 "ad937x_gain_ctrl_config.hpp"
+
+using namespace mpm::ad937x::gpio;
+using namespace mpm::ad937x::device;
+using namespace uhd;
+
+const uint8_t ad937x_gain_ctrl_channel_t::DEFAULT_GAIN_STEP = 1;
+const bool ad937x_gain_ctrl_channel_t::DEFAULT_ENABLE = 0;
+
+// rx uses gain, tx uses attenuation
+enum class pin_direction_t
+{
+ INCREASE,
+ DECREASE,
+};
+
+mykonosGpioSelect_t _convert_gain_pin(gain_pin_t pin)
+{
+ switch (pin)
+ {
+ case gain_pin_t::PIN0: return MYKGPIO0;
+ case gain_pin_t::PIN1: return MYKGPIO1;
+ case gain_pin_t::PIN2: return MYKGPIO2;
+ case gain_pin_t::PIN3: return MYKGPIO3;
+ case gain_pin_t::PIN4: return MYKGPIO4;
+ case gain_pin_t::PIN5: return MYKGPIO5;
+ case gain_pin_t::PIN6: return MYKGPIO6;
+ case gain_pin_t::PIN7: return MYKGPIO7;
+ case gain_pin_t::PIN8: return MYKGPIO8;
+ case gain_pin_t::PIN9: return MYKGPIO9;
+ case gain_pin_t::PIN10: return MYKGPIO10;
+ case gain_pin_t::PIN11: return MYKGPIO11;
+ case gain_pin_t::PIN12: return MYKGPIO12;
+ case gain_pin_t::PIN13: return MYKGPIO13;
+ case gain_pin_t::PIN14: return MYKGPIO14;
+ case gain_pin_t::PIN15: return MYKGPIO15;
+ case gain_pin_t::PIN16: return MYKGPIO16;
+ case gain_pin_t::PIN17: return MYKGPIO17;
+ case gain_pin_t::PIN18: return MYKGPIO18;
+ default: return MYKGPIONAN;
+ }
+}
+
+ad937x_gain_ctrl_channel_t::ad937x_gain_ctrl_channel_t(mykonosGpioSelect_t inc_pin, mykonosGpioSelect_t dec_pin) :
+ enable(DEFAULT_ENABLE),
+ inc_step(DEFAULT_GAIN_STEP),
+ dec_step(DEFAULT_GAIN_STEP),
+ inc_pin(inc_pin),
+ dec_pin(dec_pin)
+{
+
+}
+
+mykonosGpioSelect_t _get_gain_pin(
+ direction_t direction,
+ chain_t chain,
+ pin_direction_t pin_direction,
+ const gain_pins_t & gain_pins)
+{
+ switch (direction)
+ {
+ case RX_DIRECTION:
+ switch (chain)
+ {
+ case chain_t::ONE:
+ switch (pin_direction)
+ {
+ case pin_direction_t::INCREASE: return _convert_gain_pin(gain_pins.rx1_inc_gain_pin);
+ case pin_direction_t::DECREASE: return _convert_gain_pin(gain_pins.rx1_dec_gain_pin);
+ }
+ case chain_t::TWO:
+ switch (pin_direction)
+ {
+ case pin_direction_t::INCREASE: return _convert_gain_pin(gain_pins.rx2_inc_gain_pin);
+ case pin_direction_t::DECREASE: return _convert_gain_pin(gain_pins.rx2_dec_gain_pin);
+ }
+ }
+
+ // !!! TX is attenuation direction, so the pins are flipped !!!
+ case TX_DIRECTION:
+ switch (chain)
+ {
+ case chain_t::ONE:
+ switch (pin_direction)
+ {
+ case pin_direction_t::INCREASE: return _convert_gain_pin(gain_pins.tx1_dec_gain_pin);
+ case pin_direction_t::DECREASE: return _convert_gain_pin(gain_pins.tx1_inc_gain_pin);
+ }
+ case chain_t::TWO:
+ switch (pin_direction)
+ {
+ case pin_direction_t::INCREASE: return _convert_gain_pin(gain_pins.tx2_dec_gain_pin);
+ case pin_direction_t::DECREASE: return _convert_gain_pin(gain_pins.tx2_inc_gain_pin);
+ }
+ }
+
+ default:
+ return MYKGPIONAN;
+ }
+}
+
+ad937x_gain_ctrl_config_t::ad937x_gain_ctrl_config_t(gain_pins_t gain_pins)
+{
+ config.emplace(std::piecewise_construct, std::forward_as_tuple(RX_DIRECTION), std::forward_as_tuple());
+ config.emplace(std::piecewise_construct, std::forward_as_tuple(TX_DIRECTION), std::forward_as_tuple());
+ config.at(RX_DIRECTION).emplace(std::piecewise_construct, std::forward_as_tuple(chain_t::ONE),
+ std::forward_as_tuple(
+ _get_gain_pin(RX_DIRECTION, chain_t::ONE, pin_direction_t::INCREASE, gain_pins),
+ _get_gain_pin(RX_DIRECTION, chain_t::ONE, pin_direction_t::DECREASE, gain_pins)));
+ config.at(RX_DIRECTION).emplace(std::piecewise_construct, std::forward_as_tuple(chain_t::TWO),
+ std::forward_as_tuple(
+ _get_gain_pin(RX_DIRECTION, chain_t::TWO, pin_direction_t::INCREASE, gain_pins),
+ _get_gain_pin(RX_DIRECTION, chain_t::TWO, pin_direction_t::DECREASE, gain_pins)));
+
+ config.at(TX_DIRECTION).emplace(std::piecewise_construct, std::forward_as_tuple(chain_t::ONE),
+ std::forward_as_tuple(
+ _get_gain_pin(TX_DIRECTION, chain_t::ONE, pin_direction_t::INCREASE, gain_pins),
+ _get_gain_pin(TX_DIRECTION, chain_t::ONE, pin_direction_t::DECREASE, gain_pins)));
+ config.at(TX_DIRECTION).emplace(std::piecewise_construct, std::forward_as_tuple(chain_t::TWO),
+ std::forward_as_tuple(
+ _get_gain_pin(TX_DIRECTION, chain_t::TWO, pin_direction_t::INCREASE, gain_pins),
+ _get_gain_pin(TX_DIRECTION, chain_t::TWO, pin_direction_t::DECREASE, gain_pins)));
+}
+
diff --git a/mpm/lib/mykonos/config/ad937x_gain_ctrl_config.hpp b/mpm/lib/mykonos/config/ad937x_gain_ctrl_config.hpp
new file mode 100644
index 000000000..37c84e36c
--- /dev/null
+++ b/mpm/lib/mykonos/config/ad937x_gain_ctrl_config.hpp
@@ -0,0 +1,72 @@
+//
+// Copyright 2017 Ettus Research (National Instruments)
+//
+// 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/>.
+//
+
+#pragma once
+
+#include "../ad937x_device_types.hpp"
+#include "../adi/t_mykonos.h"
+
+// TODO: fix paths for the config subfolder
+#include "../../../include/mpm/ad937x/ad937x_ctrl_types.hpp"
+
+#include <vector>
+#include <unordered_map>
+
+struct ad937x_gain_ctrl_channel_t
+{
+ uint8_t enable;
+ uint8_t inc_step;
+ uint8_t dec_step;
+ mykonosGpioSelect_t inc_pin;
+ mykonosGpioSelect_t dec_pin;
+
+ ad937x_gain_ctrl_channel_t(mykonosGpioSelect_t inc_pin, mykonosGpioSelect_t dec_pin);
+
+private:
+ const static uint8_t DEFAULT_GAIN_STEP;
+ const static bool DEFAULT_ENABLE;
+};
+
+// C++14 requires std::hash includes a specialization for enums, but gcc doesn't do that yet
+// Remove this when that happens
+namespace std {
+ template <> struct hash<uhd::direction_t>
+ {
+ size_t operator()(const uhd::direction_t & x) const
+ {
+ return static_cast<std::size_t>(x);
+ }
+ };
+
+ template <> struct hash<mpm::ad937x::device::chain_t>
+ {
+ size_t operator()(const mpm::ad937x::device::chain_t & x) const
+ {
+ return static_cast<std::size_t>(x);
+ }
+ };
+}
+
+struct ad937x_gain_ctrl_config_t
+{
+ std::unordered_map<uhd::direction_t,
+ std::unordered_map<mpm::ad937x::device::chain_t, ad937x_gain_ctrl_channel_t>> config;
+
+ ad937x_gain_ctrl_config_t(mpm::ad937x::gpio::gain_pins_t gain_pins);
+};
+
+