diff options
Diffstat (limited to 'mpm/lib')
| -rw-r--r-- | mpm/lib/mykonos/ad937x_ctrl.cpp | 21 | ||||
| -rw-r--r-- | mpm/lib/mykonos/ad937x_device.cpp | 610 | ||||
| -rw-r--r-- | mpm/lib/mykonos/ad937x_device.hpp | 28 | ||||
| -rw-r--r-- | mpm/lib/mykonos/config/ad937x_config_t.cpp | 24 | ||||
| -rw-r--r-- | mpm/lib/mykonos/config/ad937x_config_t.hpp | 9 | ||||
| -rw-r--r-- | mpm/lib/mykonos/config/ad937x_default_config.hpp | 4 | 
6 files changed, 460 insertions, 236 deletions
diff --git a/mpm/lib/mykonos/ad937x_ctrl.cpp b/mpm/lib/mykonos/ad937x_ctrl.cpp index 55479fb1d..d859195bc 100644 --- a/mpm/lib/mykonos/ad937x_ctrl.cpp +++ b/mpm/lib/mykonos/ad937x_ctrl.cpp @@ -157,6 +157,18 @@ public:          device.start_jesd_tx();      } +    virtual void start_radio() +    { +        std::lock_guard<std::mutex> lock(*spi_mutex); +        device.start_radio(); +    } + +    virtual void stop_radio() +    { +        std::lock_guard<std::mutex> lock(*spi_mutex); +        device.stop_radio(); +    } +      virtual uint8_t get_multichip_sync_status()      {          std::lock_guard<std::mutex> lock(*spi_mutex); @@ -236,6 +248,15 @@ public:          return device.set_gain(dir, chain, value);      } +    virtual double get_gain(const std::string &which) +    { +        auto dir = _get_direction_from_antenna(which); +        auto chain = _get_chain_from_antenna(which); + +        std::lock_guard<std::mutex> lock(*spi_mutex); +        return device.get_gain(dir, chain); +    } +      // 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) diff --git a/mpm/lib/mykonos/ad937x_device.cpp b/mpm/lib/mykonos/ad937x_device.cpp index e9815112e..511a0a0a1 100644 --- a/mpm/lib/mykonos/ad937x_device.cpp +++ b/mpm/lib/mykonos/ad937x_device.cpp @@ -45,56 +45,61 @@ static const double TX_DEFAULT_FREQ = 2.5e9;  static const double RX_DEFAULT_GAIN = 0;  static const double TX_DEFAULT_GAIN = 0; -// TODO: get the actual device ID -static const uint32_t AD9371_PRODUCT_ID = 0x1; - -// TODO: move this to whereever we declare the ARM binary +static const uint32_t AD9371_PRODUCT_ID = 0x3;  static const size_t ARM_BINARY_SIZE = 98304; +static const size_t PLL_LOCK_TIMEOUT_MS = 200;  static const uint32_t INIT_CAL_TIMEOUT_MS = 10000;  // TODO: actually figure out what cals we want to run +// minimum required cals are 0x4F  static const uint32_t INIT_CALS =      TX_BB_FILTER |      ADC_TUNER |      TIA_3DB_CORNER |      DC_OFFSET | -    TX_ATTENUATION_DELAY | -    RX_GAIN_DELAY | +//    TX_ATTENUATION_DELAY | +//    RX_GAIN_DELAY |      FLASH_CAL | -    PATH_DELAY | -    TX_LO_LEAKAGE_INTERNAL | -//  TX_LO_LEAKAGE_EXTERNAL | -    TX_QEC_INIT | -    LOOPBACK_RX_LO_DELAY | -    LOOPBACK_RX_RX_QEC_INIT | -    RX_LO_DELAY | -    RX_QEC_INIT | -//  DPD_INIT | -//  CLGC_INIT | -//  VSWR_INIT | +//    PATH_DELAY | +//    TX_LO_LEAKAGE_INTERNAL | +////  TX_LO_LEAKAGE_EXTERNAL | +//    TX_QEC_INIT | +//    LOOPBACK_RX_LO_DELAY | +//    LOOPBACK_RX_RX_QEC_INIT | +//    RX_LO_DELAY | +//    RX_QEC_INIT | +////  DPD_INIT | +////  CLGC_INIT | +////  VSWR_INIT |      0;  static const uint32_t TRACKING_CALS = -    TRACK_RX1_QEC | -    TRACK_RX2_QEC | -    TRACK_ORX1_QEC | -    TRACK_ORX2_QEC | -//  TRACK_TX1_LOL | -//  TRACK_TX2_LOL | -    TRACK_TX1_QEC | -    TRACK_TX2_QEC | -//  TRACK_TX1_DPD | -//  TRACK_TX2_DPD | -//  TRACK_TX1_CLGC | -//  TRACK_TX2_CLGC | -//  TRACK_TX1_VSWR | -//  TRACK_TX2_VSWR | -//  TRACK_ORX1_QEC_SNLO | -//  TRACK_ORX2_QEC_SNLO | -//  TRACK_SRX_QEC | +//    TRACK_RX1_QEC | +//    TRACK_RX2_QEC | +//    TRACK_ORX1_QEC | +//    TRACK_ORX2_QEC | +////  TRACK_TX1_LOL | +////  TRACK_TX2_LOL | +//    TRACK_TX1_QEC | +//    TRACK_TX2_QEC | +////  TRACK_TX1_DPD | +////  TRACK_TX2_DPD | +////  TRACK_TX1_CLGC | +////  TRACK_TX2_CLGC | +////  TRACK_TX1_VSWR | +////  TRACK_TX2_VSWR | +////  TRACK_ORX1_QEC_SNLO | +////  TRACK_ORX2_QEC_SNLO | +////  TRACK_SRX_QEC |      0; + + +/****************************************************** +Helper functions +******************************************************/ +  // helper function to unify error handling  void ad937x_device::_call_api_function(std::function<mykonosErr_t()> func)  { @@ -115,6 +120,37 @@ void ad937x_device::_call_gpio_api_function(std::function<mykonosGpioErr_t()> fu      }  } +// _move_to_config_state() and _restore_from_config_state() are a pair of functions +// that should be called at the beginning and end (respectively) of any configuration +// function that requires the AD9371 to be in the radioOff state.  _restore should be +// called with the return value of _move. + +// read the current state of the AD9371 and change it to radioOff (READY) +// returns the current state, to later be consumed by _restore_from_config_state() +ad937x_device::radio_state_t ad937x_device::_move_to_config_state() +{ +    uint32_t status; +    _call_api_function(std::bind(MYKONOS_getRadioState, mykonos_config.device, &status)); +    if ((status & 0x3) == 0x3) +    { +        stop_radio(); +        return radio_state_t::ON; +    } +    else { +        return radio_state_t::OFF; +    } +} + +// restores the state from before a call to _move_to_config_state +// if ON, move to radioOn, otherwise this function is a no-op +void ad937x_device::_restore_from_config_state(ad937x_device::radio_state_t state) +{ +    if (state == radio_state_t::ON) +    { +        start_radio(); +    } +} +  std::string ad937x_device::_get_arm_binary_path()  {      // TODO: possibly add more options here, for now it's always in /lib/firmware or we explode @@ -128,44 +164,20 @@ std::vector<uint8_t> ad937x_device::_get_arm_binary()      if (!file.is_open())      {          throw mpm::runtime_error("Could not open AD9371 ARM binary at path " + path); -        return{}; +        return {};      } +    // TODO: add check that opened file size is equal to ARM_BINARY_SIZE      std::vector<uint8_t> binary(ARM_BINARY_SIZE);      file.read(reinterpret_cast<char*>(binary.data()), ARM_BINARY_SIZE);      if (file.bad())      {          throw mpm::runtime_error("Error reading AD9371 ARM binary at path " + path); +        return {};      }      return binary;  } -void ad937x_device::_initialize_rf() -{ -    // Set frequencies -    tune(uhd::RX_DIRECTION, RX_DEFAULT_FREQ, true); -    tune(uhd::TX_DIRECTION, TX_DEFAULT_FREQ, true); - -    if (!get_pll_lock_status(pll_t::CLK_SYNTH)) -    { -        throw mpm::runtime_error("CLK SYNTH PLL became unlocked!"); -    } - -    // Set gain control GPIO pins -    _apply_gain_pins(uhd::RX_DIRECTION, chain_t::ONE); -    _apply_gain_pins(uhd::RX_DIRECTION, chain_t::TWO); -    _apply_gain_pins(uhd::TX_DIRECTION, chain_t::ONE); -    _apply_gain_pins(uhd::TX_DIRECTION, chain_t::TWO); - -    // Set manual gain values -    set_gain(uhd::RX_DIRECTION, chain_t::ONE, RX_DEFAULT_GAIN); -    set_gain(uhd::RX_DIRECTION, chain_t::TWO, RX_DEFAULT_GAIN); -    set_gain(uhd::TX_DIRECTION, chain_t::ONE, TX_DEFAULT_GAIN); -    set_gain(uhd::TX_DIRECTION, chain_t::TWO, TX_DEFAULT_GAIN); - -    // TODO: add calibration stuff -} -  void ad937x_device::_verify_product_id()  {      uint8_t product_id = get_product_id(); @@ -191,13 +203,166 @@ void ad937x_device::_verify_multichip_sync_status(multichip_sync_t mcs)      }  } +// RX Gain values are table entries given in mykonos_user.h +// An array of gain values is programmed at initialization, which the API will then use for its gain values +// In general, Gain Value = (255 - Gain Table Index) +uint8_t ad937x_device::_convert_rx_gain_to_mykonos(double gain) +{ +    // TODO: derive 195 constant from gain table +    // gain should be a value 0-60, add 195 to make 195-255 +    return static_cast<uint8_t>((gain * 2) + 195); +} + +double ad937x_device::_convert_rx_gain_from_mykonos(uint8_t gain) +{ +    return (static_cast<double>(gain) - 195) / 2.0; +} + +// TX gain is completely different from RX gain for no good reason so deal with it +// TX is set as attenuation using a value from 0-41950 mdB +// Only increments of 50 mdB are valid +uint16_t ad937x_device::_convert_tx_gain_to_mykonos(double gain) +{ +    // attenuation is inverted and in mdB not dB +    return static_cast<uint16_t>((MAX_TX_GAIN - (gain)) * 1e3); +} + +double ad937x_device::_convert_tx_gain_from_mykonos(uint16_t gain) +{ +    return (MAX_TX_GAIN - (static_cast<double>(gain) / 1e3)); +} + +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) +    { +        MPM_ASSERT_THROW(chan.inc_step == chan.dec_step); +    } + +    auto state = _move_to_config_state(); + +    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)); +            break; +        } +        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)); +            break; +        } +    } +    _restore_from_config_state(state); +} + + + +/****************************************************** +Initialization functions +******************************************************/ + +ad937x_device::ad937x_device( +    mpm::types::regs_iface* iface, +    gain_pins_t gain_pins) : +    full_spi_settings(iface), +    mykonos_config(&full_spi_settings.spi_settings), +    gain_ctrl(gain_pins) +{ +} + +void ad937x_device::_initialize_rf() +{ +    // TODO: add setRfPllLoopFilter here when we upgrade the API to >3546 + +    // Set frequencies +    tune(uhd::RX_DIRECTION, RX_DEFAULT_FREQ, false); +    tune(uhd::TX_DIRECTION, TX_DEFAULT_FREQ, false); + +    if (!get_pll_lock_status(CLK_SYNTH | RX_SYNTH | TX_SYNTH | SNIFF_SYNTH, true)) +    { +        throw mpm::runtime_error("PLLs did not lock after initial tuning!"); +    } + +    // Set gain control GPIO pins +    _apply_gain_pins(uhd::RX_DIRECTION, chain_t::ONE); +    _apply_gain_pins(uhd::RX_DIRECTION, chain_t::TWO); +    _apply_gain_pins(uhd::TX_DIRECTION, chain_t::ONE); +    _apply_gain_pins(uhd::TX_DIRECTION, chain_t::TWO); + +    _call_gpio_api_function(std::bind(MYKONOS_setupGpio, mykonos_config.device)); + +    // Set manual gain values +    set_gain(uhd::RX_DIRECTION, chain_t::ONE, RX_DEFAULT_GAIN); +    set_gain(uhd::RX_DIRECTION, chain_t::TWO, RX_DEFAULT_GAIN); +    set_gain(uhd::TX_DIRECTION, chain_t::ONE, TX_DEFAULT_GAIN); +    set_gain(uhd::TX_DIRECTION, chain_t::TWO, TX_DEFAULT_GAIN); + +    // Run and wait for init cals +    _call_api_function(std::bind(MYKONOS_runInitCals, mykonos_config.device, INIT_CALS)); + +    uint8_t errorFlag = 0, errorCode = 0; +    _call_api_function(std::bind(MYKONOS_waitInitCals, mykonos_config.device, INIT_CAL_TIMEOUT_MS, &errorFlag, &errorCode)); + +    if ((errorFlag != 0) || (errorCode != 0)) +    { +        throw mpm::runtime_error("Init cals failed!"); +        // TODO: add more debugging information here +    } + +    _call_api_function(std::bind(MYKONOS_enableTrackingCals, mykonos_config.device, TRACKING_CALS)); +    // ready for radioOn +} +  void ad937x_device::begin_initialization()  {      _call_api_function(std::bind(MYKONOS_initialize, mykonos_config.device));      _verify_product_id(); -    if (!get_pll_lock_status(pll_t::CLK_SYNTH)) +    if (!get_pll_lock_status(CLK_SYNTH))      {          throw mpm::runtime_error("AD937x CLK_SYNTH PLL failed to lock");      } @@ -232,6 +397,22 @@ void ad937x_device::start_jesd_rx()      _call_api_function(std::bind(MYKONOS_enableSysrefToDeframer, mykonos_config.device, 1));  } +void ad937x_device::start_radio() +{ +    _call_api_function(std::bind(MYKONOS_radioOn, mykonos_config.device)); +} + +void ad937x_device::stop_radio() +{ +    _call_api_function(std::bind(MYKONOS_radioOff, mykonos_config.device)); +} + + + +/****************************************************** +Get status functions +******************************************************/ +  uint8_t ad937x_device::get_multichip_sync_status()  {      uint8_t mcs_status = 0; @@ -261,21 +442,6 @@ uint16_t ad937x_device::get_ilas_config_match()      return ilas_status;  } -void ad937x_device::enable_jesd_loopback(uint8_t enable) -{ -    _call_api_function(std::bind(MYKONOS_setRxFramerDataSource, mykonos_config.device, enable)); -} - -ad937x_device::ad937x_device( -        mpm::types::regs_iface* iface, -        gain_pins_t gain_pins -) : -    full_spi_settings(iface), -    mykonos_config(&full_spi_settings.spi_settings), -    gain_ctrl(gain_pins) -{ -} -  uint8_t ad937x_device::get_product_id()  {      uint8_t id; @@ -313,11 +479,28 @@ arm_version_t ad937x_device::get_arm_version()      return arm;  } + + +/****************************************************** +Set configuration functions +******************************************************/ + +void ad937x_device::enable_jesd_loopback(uint8_t enable) +{ +    auto state = _move_to_config_state(); +    _call_api_function(std::bind(MYKONOS_setRxFramerDataSource, mykonos_config.device, enable)); +    _restore_from_config_state(state); +} +  double ad937x_device::set_clock_rate(double req_rate)  {      auto rate = static_cast<uint32_t>(req_rate / 1000.0); + +    auto state = _move_to_config_state();      mykonos_config.device->clocks->deviceClock_kHz = rate;      _call_api_function(std::bind(MYKONOS_initDigitalClocks, mykonos_config.device)); +    _restore_from_config_state(state); +      return static_cast<double>(rate);  } @@ -326,6 +509,9 @@ void ad937x_device::enable_channel(direction_t direction, chain_t chain, bool en      // TODO:      // Turns out the only code in the API that actually sets the channel enable settings      // is _initialize(). Need to figure out how to deal with this. +    // mmeserve 8/24/2017 +    // While it is possible to change the enable state after disabling the radio, we'll probably +    // always use the GPIO pins to do so. Delete this function at a later time.  }  double ad937x_device::tune(direction_t direction, double value, bool wait_for_lock = false) @@ -334,91 +520,39 @@ double ad937x_device::tune(direction_t direction, double value, bool wait_for_lo      // but here it is      mykonosRfPllName_t pll; -    pll_t locked_pll; +    uint8_t locked_pll; +    uint64_t* config_value;      uint64_t integer_value = static_cast<uint64_t>(value);      switch (direction)      {      case TX_DIRECTION:          pll = TX_PLL; -        locked_pll = pll_t::TX_SYNTH; -        mykonos_config.device->tx->txPllLoFrequency_Hz = integer_value; +        locked_pll = TX_SYNTH; +        config_value = &(mykonos_config.device->tx->txPllLoFrequency_Hz);          break;      case RX_DIRECTION:          pll = RX_PLL; -        locked_pll = pll_t::RX_SYNTH; -        mykonos_config.device->rx->rxPllLoFrequency_Hz = integer_value; +        locked_pll = RX_SYNTH; +        config_value = &(mykonos_config.device->rx->rxPllLoFrequency_Hz);          break;      default:          MPM_THROW_INVALID_CODE_PATH();      } +    auto state = _move_to_config_state(); +    *config_value = integer_value;      _call_api_function(std::bind(MYKONOS_setRfPllFrequency, mykonos_config.device, pll, integer_value)); -    auto lock_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(200); - -    // TODO: coercion here causes extra device accesses, when the formula is provided on pg 119 of the user guide -    // Furthermore, because coerced is returned as an integer, it's not even accurate -    uint64_t coerced_pll; -    _call_api_function(std::bind(MYKONOS_getRfPllFrequency, mykonos_config.device, pll, &coerced_pll));      if (wait_for_lock)      { -        bool locked = false; -        while (not locked and lock_time > std::chrono::steady_clock::now()) -        { -            locked = get_pll_lock_status(locked_pll); -        } - -        if (!locked) +        if (!get_pll_lock_status(locked_pll, true))          { -            if (!get_pll_lock_status(locked_pll)) // last chance -            { -                throw mpm::runtime_error("RF PLL did not lock"); -            } +            throw mpm::runtime_error("PLL did not lock");          }      } +    _restore_from_config_state(state); -    return static_cast<double>(coerced_pll); -} - -double ad937x_device::get_freq(direction_t direction) -{ -    mykonosRfPllName_t pll; -    switch (direction) -    { -    case TX_DIRECTION: pll = TX_PLL; break; -    case RX_DIRECTION: pll = RX_PLL; break; -    default: -        MPM_THROW_INVALID_CODE_PATH(); -    } - -    // TODO: coercion here causes extra device accesses, when the formula is provided on pg 119 of the user guide -    // Furthermore, because coerced is returned as an integer, it's not even accurate -    uint64_t coerced_pll; -    _call_api_function(std::bind(MYKONOS_getRfPllFrequency, mykonos_config.device, pll, &coerced_pll)); -    return static_cast<double>(coerced_pll); -} - -bool ad937x_device::get_pll_lock_status(pll_t pll) -{ -    uint8_t pll_status; -    _call_api_function(std::bind(MYKONOS_checkPllsLockStatus, mykonos_config.device, &pll_status)); - -    switch (pll) -    { -    case pll_t::CLK_SYNTH: -        return (pll_status & 0x01) > 0; -    case pll_t::RX_SYNTH: -        return (pll_status & 0x02) > 0; -    case pll_t::TX_SYNTH: -        return (pll_status & 0x04) > 0; -    case pll_t::SNIFF_SYNTH: -        return (pll_status & 0x08) > 0; -    case pll_t::CALPLL_SDM: -        return (pll_status & 0x10) > 0; -    default: -        MPM_THROW_INVALID_CODE_PATH(); -        return false; -    } +    return get_freq(direction);  }  double ad937x_device::set_bw_filter(direction_t direction, chain_t chain, double value) @@ -427,33 +561,16 @@ double ad937x_device::set_bw_filter(direction_t direction, chain_t chain, double      return double();  } -// RX Gain values are table entries given in mykonos_user.h -// An array of gain values is programmed at initialization, which the API will then use for its gain values -// In general, Gain Value = (255 - Gain Table Index) -uint8_t ad937x_device::_convert_rx_gain(double gain) -{ -    // gain should be a value 0-60, add 195 to make 195-255 -    return static_cast<uint8_t>((gain * 2) + 195); -} - -// TX gain is completely different from RX gain for no good reason so deal with it -// TX is set as attenuation using a value from 0-41950 mdB -// Only increments of 50 mdB are valid -uint16_t ad937x_device::_convert_tx_gain(double gain) -{ -    // attenuation is inverted and in mdB not dB -    return static_cast<uint16_t>((MAX_TX_GAIN - (gain)) * 1e3); -} -  double ad937x_device::set_gain(direction_t direction, chain_t chain, double value)  {      double coerced_value; +    auto state = _move_to_config_state();      switch (direction)      {      case TX_DIRECTION:      { -        uint16_t attenuation = _convert_tx_gain(value); +        uint16_t attenuation = _convert_tx_gain_to_mykonos(value);          coerced_value = static_cast<double>(attenuation);          std::function<mykonosErr_t(mykonosDevice_t*, uint16_t)> func; @@ -473,7 +590,7 @@ double ad937x_device::set_gain(direction_t direction, chain_t chain, double valu      }      case RX_DIRECTION:      { -        uint8_t gain = _convert_rx_gain(value); +        uint8_t gain = _convert_rx_gain_to_mykonos(value);          coerced_value = static_cast<double>(gain);          std::function<mykonosErr_t(mykonosDevice_t*, uint8_t)> func; @@ -494,31 +611,40 @@ double ad937x_device::set_gain(direction_t direction, chain_t chain, double valu      default:          MPM_THROW_INVALID_CODE_PATH();      } + +    _restore_from_config_state(state); +    // TODO: coerced_value here is wrong, should just call get_gain      return coerced_value;  }  void ad937x_device::set_agc_mode(direction_t direction, gain_mode_t mode)  { +    mykonosGainMode_t mykonos_mode;      switch (direction)      {      case RX_DIRECTION:          switch (mode)          {          case gain_mode_t::MANUAL: -            _call_api_function(std::bind(MYKONOS_setRxGainControlMode, mykonos_config.device, MGC)); +            mykonos_mode = MGC;              break;          case gain_mode_t::AUTOMATIC: -            _call_api_function(std::bind(MYKONOS_setRxGainControlMode, mykonos_config.device, AGC)); +            mykonos_mode = AGC;              break;          case gain_mode_t::HYBRID: -            _call_api_function(std::bind(MYKONOS_setRxGainControlMode, mykonos_config.device, HYBRID)); +            mykonos_mode = HYBRID;              break;          default:              MPM_THROW_INVALID_CODE_PATH();          } +        break;      default:          MPM_THROW_INVALID_CODE_PATH();      } + +    auto state = _move_to_config_state(); +    _call_api_function(std::bind(MYKONOS_setRxGainControlMode, mykonos_config.device, mykonos_mode)); +    _restore_from_config_state(state);  }  void ad937x_device::set_fir( @@ -538,30 +664,26 @@ void ad937x_device::set_fir(      default:          MPM_THROW_INVALID_CODE_PATH();      } + +    // TODO: reload this on device  } -std::vector<int16_t> ad937x_device::get_fir( -    const direction_t direction, -    const chain_t chain, -    int8_t &gain) +void ad937x_device::set_gain_pin_step_sizes(direction_t direction, chain_t chain, double inc_step, double dec_step)  { -    switch (direction) +    if (direction == RX_DIRECTION)      { -    case TX_DIRECTION: -        return mykonos_config.tx_fir_config.get_fir(gain); -    case RX_DIRECTION: -        return mykonos_config.rx_fir_config.get_fir(gain); -    default: +        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 {          MPM_THROW_INVALID_CODE_PATH();      } -} - -int16_t ad937x_device::get_temperature() -{ -    // TODO: deal with the status.tempValid flag -    mykonosTempSensorStatus_t status; -    _call_gpio_api_function(std::bind(MYKONOS_readTempSensor, mykonos_config.device, &status)); -    return status.tempCode; +    _apply_gain_pins(direction, chain);  }  void ad937x_device::set_enable_gain_pins(direction_t direction, chain_t chain, bool enable) @@ -570,80 +692,118 @@ void ad937x_device::set_enable_gain_pins(direction_t direction, chain_t chain, b      _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) + + +/****************************************************** +Get configuration functions +******************************************************/ + +double ad937x_device::get_freq(direction_t direction)  { -    if (direction == RX_DIRECTION) +    mykonosRfPllName_t pll; +    switch (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 { +    case TX_DIRECTION: pll = TX_PLL; break; +    case RX_DIRECTION: pll = RX_PLL; break; +    default:          MPM_THROW_INVALID_CODE_PATH();      } -    _apply_gain_pins(direction, chain); + +    // TODO: coercion here causes extra device accesses, when the formula is provided on pg 119 of the user guide +    // Furthermore, because coerced is returned as an integer, it's not even accurate +    uint64_t coerced_pll; +    _call_api_function(std::bind(MYKONOS_getRfPllFrequency, mykonos_config.device, pll, &coerced_pll)); +    return static_cast<double>(coerced_pll);  } -void ad937x_device::_apply_gain_pins(direction_t direction, chain_t chain) +bool ad937x_device::get_pll_lock_status(uint8_t pll, bool wait_for_lock)  { -    using namespace std::placeholders; - -    // get this channels configuration -    auto chan = gain_ctrl.config.at(direction).at(chain); +    uint8_t pll_status; +    _call_api_function(std::bind(MYKONOS_checkPllsLockStatus, mykonos_config.device, &pll_status)); -    // TX direction does not support different steps per direction -    if (direction == TX_DIRECTION) +    if (not wait_for_lock)      { -        MPM_ASSERT_THROW(chan.inc_step == chan.dec_step); +        return (pll_status & pll) == pll;      } +    else { +        auto lock_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(PLL_LOCK_TIMEOUT_MS); +        bool locked = false; +        while (not locked and lock_time > std::chrono::steady_clock::now()) +        { +            locked = get_pll_lock_status(pll); +        } +        if (!locked) +        { +            // last chance +            locked = get_pll_lock_status(pll); +        } +        return locked; +    } +} + +double ad937x_device::get_gain(direction_t direction, chain_t chain) +{      switch (direction)      { -        case RX_DIRECTION: +        case TX_DIRECTION:          { -            std::function<decltype(MYKONOS_setRx1GainCtrlPin)> func; +            std::function<mykonosErr_t(mykonosDevice_t*, uint16_t*)> func;              switch (chain)              {              case chain_t::ONE: -                func = MYKONOS_setRx1GainCtrlPin; +                func = MYKONOS_getTx1Attenuation;                  break;              case chain_t::TWO: -                func = MYKONOS_setRx2GainCtrlPin; +                func = MYKONOS_getTx2Attenuation;                  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)); +            uint16_t atten; +            _call_api_function(std::bind(func, mykonos_config.device, &atten)); +            return _convert_tx_gain_from_mykonos(atten);          } -        case TX_DIRECTION: +        case RX_DIRECTION:          { -            // TX sets attenuation, but the configuration should be stored correctly -            std::function<decltype(MYKONOS_setTx2AttenCtrlPin)> func; +            std::function<mykonosErr_t(mykonosDevice_t*, uint8_t*)> 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); +                func = MYKONOS_getRx1Gain;                  break;              case chain_t::TWO: -                func = MYKONOS_setTx2AttenCtrlPin; +                func = MYKONOS_getRx2Gain;                  break;              } -            _call_gpio_api_function( -                std::bind(func, -                    mykonos_config.device, -                    chan.inc_step, -                    chan.inc_pin, -                    chan.dec_pin, -                    chan.enable)); +            uint8_t gain; +            _call_api_function(std::bind(func, mykonos_config.device, &gain)); +            return _convert_rx_gain_from_mykonos(gain);          } +        default: +            MPM_THROW_INVALID_CODE_PATH();      }  } +std::vector<int16_t> ad937x_device::get_fir( +    const direction_t direction, +    const chain_t chain, +    int8_t &gain) +{ +    switch (direction) +    { +    case TX_DIRECTION: +        return mykonos_config.tx_fir_config.get_fir(gain); +    case RX_DIRECTION: +        return mykonos_config.rx_fir_config.get_fir(gain); +    default: +        MPM_THROW_INVALID_CODE_PATH(); +    } +} + +int16_t ad937x_device::get_temperature() +{ +    // TODO: deal with the status.tempValid flag +    mykonosTempSensorStatus_t status; +    _call_gpio_api_function(std::bind(MYKONOS_readTempSensor, mykonos_config.device, &status)); +    return status.tempCode; +} + diff --git a/mpm/lib/mykonos/ad937x_device.hpp b/mpm/lib/mykonos/ad937x_device.hpp index b20feb3f7..4797ed5ef 100644 --- a/mpm/lib/mykonos/ad937x_device.hpp +++ b/mpm/lib/mykonos/ad937x_device.hpp @@ -38,7 +38,14 @@ class ad937x_device : public boost::noncopyable  {  public:      enum class gain_mode_t { MANUAL, AUTOMATIC, HYBRID }; -    enum class pll_t { CLK_SYNTH, RX_SYNTH, TX_SYNTH, SNIFF_SYNTH, CALPLL_SDM }; +    enum pll_t : uint8_t +    { +        CLK_SYNTH   = 0x01, +        RX_SYNTH    = 0x02, +        TX_SYNTH    = 0x04, +        SNIFF_SYNTH = 0x08, +        CALPLL_SDM  = 0x10, +    };      ad937x_device(          mpm::types::regs_iface* iface, @@ -49,6 +56,8 @@ public:      void finish_initialization();      void start_jesd_rx();      void start_jesd_tx(); +    void start_radio(); +    void stop_radio();      uint8_t get_multichip_sync_status();      uint8_t get_framer_status(); @@ -62,14 +71,17 @@ public:      mpm::ad937x::device::arm_version_t get_arm_version();      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, mpm::ad937x::device::chain_t chain, bool enable); + +    double set_gain(uhd::direction_t direction, mpm::ad937x::device::chain_t chain, double value); +    double get_gain(uhd::direction_t direction, mpm::ad937x::device::chain_t chain); +      double tune(uhd::direction_t direction, double value, bool wait_for_lock);      double get_freq(uhd::direction_t direction); -    bool get_pll_lock_status(pll_t pll); +    bool get_pll_lock_status(uint8_t pll, bool wait_for_lock = false);      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); @@ -90,6 +102,7 @@ public:  private:      enum class multichip_sync_t { PARTIAL, FULL }; +    enum class radio_state_t { OFF, ON };      ad9371_spiSettings_t full_spi_settings;      ad937x_config_t mykonos_config; @@ -107,6 +120,11 @@ private:      void _verify_product_id();      void _verify_multichip_sync_status(multichip_sync_t mcs); -    static uint8_t _convert_rx_gain(double gain); -    static uint16_t _convert_tx_gain(double gain); +    radio_state_t _move_to_config_state(); +    void _restore_from_config_state(radio_state_t state); + +    static uint8_t _convert_rx_gain_to_mykonos(double gain); +    static double _convert_rx_gain_from_mykonos(uint8_t gain); +    static uint16_t _convert_tx_gain_to_mykonos(double gain); +    static double _convert_tx_gain_from_mykonos(uint16_t gain);  }; diff --git a/mpm/lib/mykonos/config/ad937x_config_t.cpp b/mpm/lib/mykonos/config/ad937x_config_t.cpp index 0e6d499e6..97d0a91d5 100644 --- a/mpm/lib/mykonos/config/ad937x_config_t.cpp +++ b/mpm/lib/mykonos/config/ad937x_config_t.cpp @@ -18,6 +18,22 @@  #include "ad937x_config_t.hpp"  #include "ad937x_default_config.hpp" +const int16_t ad937x_config_t::DEFAULT_TX_FIR[DEFAULT_TX_FIR_SIZE] = +    {   -94,  -26,  282,  177, -438, -368,  756,  732,-1170,-1337, 1758, 2479,-2648,-5088, 4064,16760, +      16759, 4110,-4881,-2247, 2888, 1917,-1440,-1296,  745,  828, -358, -474,  164,  298,  -16,  -94 }; +const int16_t ad937x_config_t::DEFAULT_RX_FIR[DEFAULT_RX_FIR_SIZE] = +    {   -20,    6,   66,   22, -128,  -54,  240,  126, -402, -248,  634,  444, -956, -756, 1400, 1244, +      -2028,-2050, 2978, 3538,-4646,-7046, 9536,30880,30880, 9536,-7046,-4646, 3538, 2978,-2050,-2028, +       1244, 1400, -756, -956,  444,  634, -248, -402,  126,  240,  -54, -128,   22,   66,    6,  -20 }; +const int16_t ad937x_config_t::DEFAULT_OBSRX_FIR[DEFAULT_RX_FIR_SIZE] = +    {   -14,  -19,   44,   41,  -89,  -95,  175,  178, -303, -317,  499,  527, -779, -843, 1184, 1317, +      -1781,-2059, 2760, 3350,-4962,-7433, 9822,32154,32154, 9822,-7433,-4962, 3350, 2760,-2059,-1781, +       1317, 1184, -843, -779,  527,  499, -317, -303,  178,  175,  -95,  -89,   41,   44,  -19,  -14 }; +const int16_t ad937x_config_t::DEFAULT_SNIFFER_FIR[DEFAULT_RX_FIR_SIZE] = +    {    -1,   -5,  -14,  -23,  -16,   24,   92,  137,   80, -120, -378, -471, -174,  507, 1174, 1183, +         98,-1771,-3216,-2641,  942, 7027,13533,17738,17738,13533, 7027,  942,-2641,-3216,-1771,   98, +       1183, 1174,  507, -174, -471, -378, -120,   80,  137,   92,   24,  -16,  -23,  -14,   -5,   -1 }; +  ad937x_config_t::ad937x_config_t(spiSettings_t* sps)  {      _device.spiSettings = sps; @@ -125,9 +141,9 @@ void ad937x_config_t::_init_pointers()  void ad937x_config_t::_assign_firs()  {      // TODO: get default filters here -    tx_fir_config.set_fir(6, std::vector<int16_t>(48, 0)); -    rx_fir_config.set_fir(-6, std::vector<int16_t>(48, 0)); -    _orx_fir_config.set_fir(-6, std::vector<int16_t>(48, 0)); -    _sniffer_rx_fir_config.set_fir(-6, std::vector<int16_t>(48, 0)); +    tx_fir_config.set_fir(6, std::vector<int16_t>(DEFAULT_TX_FIR, DEFAULT_TX_FIR + DEFAULT_TX_FIR_SIZE)); +    rx_fir_config.set_fir(-6, std::vector<int16_t>(DEFAULT_RX_FIR, DEFAULT_RX_FIR + DEFAULT_RX_FIR_SIZE)); +    _orx_fir_config.set_fir(-6, std::vector<int16_t>(DEFAULT_OBSRX_FIR, DEFAULT_OBSRX_FIR + DEFAULT_RX_FIR_SIZE)); +    _sniffer_rx_fir_config.set_fir(-6, std::vector<int16_t>(DEFAULT_SNIFFER_FIR, DEFAULT_SNIFFER_FIR + DEFAULT_RX_FIR_SIZE));  } diff --git a/mpm/lib/mykonos/config/ad937x_config_t.hpp b/mpm/lib/mykonos/config/ad937x_config_t.hpp index 94d14c733..9613132e7 100644 --- a/mpm/lib/mykonos/config/ad937x_config_t.hpp +++ b/mpm/lib/mykonos/config/ad937x_config_t.hpp @@ -33,6 +33,15 @@ public:      ad937x_fir rx_fir_config;      ad937x_fir tx_fir_config; + +    static const size_t DEFAULT_TX_FIR_SIZE = 32; +    static const size_t DEFAULT_RX_FIR_SIZE = 48; + +    static const int16_t DEFAULT_TX_FIR[DEFAULT_TX_FIR_SIZE]; +    static const int16_t DEFAULT_RX_FIR[DEFAULT_RX_FIR_SIZE]; +    static const int16_t DEFAULT_OBSRX_FIR[DEFAULT_RX_FIR_SIZE]; +    static const int16_t DEFAULT_SNIFFER_FIR[DEFAULT_RX_FIR_SIZE]; +  private:      mykonosDevice_t _device; diff --git a/mpm/lib/mykonos/config/ad937x_default_config.hpp b/mpm/lib/mykonos/config/ad937x_default_config.hpp index fdf777795..614d50d55 100644 --- a/mpm/lib/mykonos/config/ad937x_default_config.hpp +++ b/mpm/lib/mykonos/config/ad937x_default_config.hpp @@ -66,7 +66,7 @@ static const mykonosJesd204bFramerConfig_t DEFAULT_FRAMER =      0,              // Flag for determining if SYSREF on relink should be set. Where, if > 0 = set, 0 = not set      0,              // Flag for determining if auto channel select for the xbar should be set. Where, if > 0 = set, '0' = not set      0,              // Selects SYNCb input source. Where, 0 = use RXSYNCB for this framer, 1 = use OBSRX_SYNCB for this framer -    0,              // Flag for determining if CMOS mode for RX Sync signal is used. Where, if > 0 = CMOS, '0' = LVDS +    1,              // Flag for determining if CMOS mode for RX Sync signal is used. Where, if > 0 = CMOS, '0' = LVDS      0               // Selects framer bit repeat or oversampling mode for lane rate matching. Where, 0 = bitRepeat mode (changes effective lanerate), 1 = overSample (maintains same lane rate between ObsRx framer and Rx framer and oversamples the ADC samples)  }; @@ -188,7 +188,7 @@ static const mykonosJesd204bDeframerConfig_t DEFAULT_DEFRAMER =      0,              // LMFC offset value to adjust deterministic latency. Range is 0..31      0,              // Flag for determining if SYSREF on relink should be set. Where, if > 0 = set, '0' = not set      0,              // Flag for determining if auto channel select for the xbar should be set. Where, if > 0 = set, '0' = not set -    0               // Flag for determining if CMOS mode for TX Sync signal is used. Where, if > 0 = CMOS, '0' = LVDS +    1               // Flag for determining if CMOS mode for TX Sync signal is used. Where, if > 0 = CMOS, '0' = LVDS  };  static const mykonosObsRxSettings_t DEFAULT_ORX_SETTINGS =  | 
