diff options
Diffstat (limited to 'host/lib/usrp')
128 files changed, 1401 insertions, 1135 deletions
diff --git a/host/lib/usrp/b100/b100_impl.cpp b/host/lib/usrp/b100/b100_impl.cpp index 1a38bf3b7..25f99e85e 100644 --- a/host/lib/usrp/b100/b100_impl.cpp +++ b/host/lib/usrp/b100/b100_impl.cpp @@ -19,7 +19,7 @@  #include "b100_impl.hpp"  #include "b100_regs.hpp"  #include <uhd/transport/usb_control.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/cast.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/static.hpp> @@ -73,17 +73,17 @@ static device_addrs_t b100_find(const device_addr_t &hint)      //find the usrps and load firmware      size_t found = 0; -    BOOST_FOREACH(usb_device_handle::sptr handle, usb_device_handle::get_device_list(vid, pid)) { +    for(usb_device_handle::sptr handle: usb_device_handle::get_device_list(vid,  pid)) {          //extract the firmware path for the b100          std::string b100_fw_image;          try{              b100_fw_image = find_image_path(hint.get("fw", B100_FW_FILE_NAME));          }          catch(...){ -            UHD_MSG(warning) << boost::format("Could not locate B100 firmware. %s\n") % print_utility_error("uhd_images_downloader.py"); +            UHD_LOGGER_WARNING("B100") << boost::format("Could not locate B100 firmware. %s\n") % print_utility_error("uhd_images_downloader.py");              return b100_addrs;          } -        UHD_LOG << "the firmware image: " << b100_fw_image << std::endl; +        UHD_LOGGER_DEBUG("B100") << "the firmware image: " << b100_fw_image ;          usb_control::sptr control;          try{control = usb_control::make(handle, 0);} @@ -102,7 +102,7 @@ static device_addrs_t b100_find(const device_addr_t &hint)      //search for the device until found or timeout      while (boost::get_system_time() < timeout_time and b100_addrs.empty() and found != 0)      { -        BOOST_FOREACH(usb_device_handle::sptr handle, usb_device_handle::get_device_list(vid, pid)) +      for(usb_device_handle::sptr handle: usb_device_handle::get_device_list(vid,  pid))          {              usb_control::sptr control;              try{control = usb_control::make(handle, 0);} @@ -161,7 +161,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      //locate the matching handle in the device list      usb_device_handle::sptr handle; -    BOOST_FOREACH(usb_device_handle::sptr dev_handle, device_list) { +    for(usb_device_handle::sptr dev_handle:  device_list) {          if (dev_handle->get_serial() == device_addr["serial"]){              handle = dev_handle;              break; @@ -202,9 +202,9 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      //try reset once in the case of failure      catch(const uhd::exception &ex){          if (initialization_count > 1) throw; -        UHD_MSG(warning) << +        UHD_LOGGER_WARNING("B100") <<              "The control endpoint was left in a bad state.\n" -            "Attempting endpoint re-enumeration...\n" << ex.what() << std::endl; +            "Attempting endpoint re-enumeration...\n" << ex.what() ;          _fifo_ctrl.reset();          _ctrl_transport.reset();          _fx2_ctrl->usrp_fx2_reset(); @@ -230,9 +230,9 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      //try reset once in the case of failure      catch(const uhd::exception &){          if (initialization_count > 1) throw; -        UHD_MSG(warning) << +        UHD_LOGGER_WARNING("B100") <<              "The control endpoint was left in a bad state.\n" -            "Attempting endpoint re-enumeration...\n" << std::endl; +            "Attempting endpoint re-enumeration...\n" ;          _fifo_ctrl.reset();          _ctrl_transport.reset();          _fx2_ctrl->usrp_fx2_reset(); @@ -478,12 +478,12 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      //bind frontend corrections to the dboard freq props      const fs_path db_tx_fe_path = mb_path / "dboards" / "A" / "tx_frontends"; -    BOOST_FOREACH(const std::string &name, _tree->list(db_tx_fe_path)){ +    for(const std::string &name:  _tree->list(db_tx_fe_path)){          _tree->access<double>(db_tx_fe_path / name / "freq" / "value")              .add_coerced_subscriber(boost::bind(&b100_impl::set_tx_fe_corrections, this, _1));      }      const fs_path db_rx_fe_path = mb_path / "dboards" / "A" / "rx_frontends"; -    BOOST_FOREACH(const std::string &name, _tree->list(db_rx_fe_path)){ +    for(const std::string &name:  _tree->list(db_rx_fe_path)){          _tree->access<double>(db_rx_fe_path / name / "freq" / "value")              .add_coerced_subscriber(boost::bind(&b100_impl::set_rx_fe_corrections, this, _1));      } @@ -504,10 +504,10 @@ b100_impl::b100_impl(const device_addr_t &device_addr){          .add_coerced_subscriber(boost::bind(&b100_clock_ctrl::set_fpga_clock_rate, _clock_ctrl, _1));      //reset cordic rates and their properties to zero -    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){ +    for(const std::string &name:  _tree->list(mb_path / "rx_dsps")){          _tree->access<double>(mb_path / "rx_dsps" / name / "freq" / "value").set(0.0);      } -    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +    for(const std::string &name:  _tree->list(mb_path / "tx_dsps")){          _tree->access<double>(mb_path / "tx_dsps" / name / "freq" / "value").set(0.0);      } diff --git a/host/lib/usrp/b100/clock_ctrl.cpp b/host/lib/usrp/b100/clock_ctrl.cpp index 5700a321a..010a0a6f8 100644 --- a/host/lib/usrp/b100/clock_ctrl.cpp +++ b/host/lib/usrp/b100/clock_ctrl.cpp @@ -18,14 +18,13 @@  #include "clock_ctrl.hpp"  #include "ad9522_regs.hpp"  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/exception.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/safe_call.hpp>  #include <stdint.h>  #include "b100_regs.hpp" //spi slave constants  #include <boost/assign/list_of.hpp> -#include <boost/foreach.hpp>  #include <boost/format.hpp>  #include <boost/thread/thread.hpp>  #include <boost/math/common_factor_rt.hpp> //gcd @@ -149,11 +148,11 @@ static clock_settings_type get_clock_settings(double rate){                  cs.chan_divider /= cs.vco_divider;              } -            UHD_LOGV(always) -                << "gcd " << gcd << std::endl -                << "X " << X << std::endl -                << "Y " << Y << std::endl -                << cs.to_pp_string() << std::endl +            UHD_LOGGER_DEBUG("B100") +                << "gcd: " << gcd +                << " X: " << X +                << " Y: " << Y +                << cs.to_pp_string()              ;              //filter limits on the counters @@ -167,7 +166,7 @@ static clock_settings_type get_clock_settings(double rate){              if (cs.get_vco_rate() < 1400e6 + vco_bound_pad) continue;              if (cs.get_out_rate() != rate) continue; -            UHD_MSG(status) << "USRP-B100 clock control: " << i << std::endl << cs.to_pp_string() << std::endl; +            UHD_LOGGER_INFO("B100") << "USRP-B100 clock control: " << i  << cs.to_pp_string() ;              return cs;          }      } @@ -466,7 +465,7 @@ private:      void send_reg(uint16_t addr){          uint32_t reg = _ad9522_regs.get_write_reg(addr); -        UHD_LOGV(often) << "clock control write reg: " << std::hex << reg << std::endl; +        UHD_LOGGER_TRACE("B100") << "clock control write reg: " << std::hex << reg ;          byte_vector_t buf;          buf.push_back(uint8_t(reg >> 16));          buf.push_back(uint8_t(reg >> 8)); @@ -502,7 +501,7 @@ private:              _ad9522_regs.set_reg(addr, reg);              if (_ad9522_regs.vco_calibration_finished) goto wait_for_ld;          } -        UHD_MSG(error) << "USRP-B100 clock control: VCO calibration timeout" << std::endl; +        UHD_LOGGER_ERROR("B100") << "USRP-B100 clock control: VCO calibration timeout";          wait_for_ld:          //wait for digital lock detect:          for (size_t ms10 = 0; ms10 < 100; ms10++){ @@ -511,7 +510,7 @@ private:              _ad9522_regs.set_reg(addr, reg);              if (_ad9522_regs.digital_lock_detect) return;          } -        UHD_MSG(error) << "USRP-B100 clock control: lock detection timeout" << std::endl; +        UHD_LOGGER_ERROR("B100") << "USRP-B100 clock control: lock detection timeout";      }      void soft_sync(void){ @@ -533,7 +532,7 @@ private:          ;          //write initial register values and latch/update -        BOOST_FOREACH(const range_t &range, ranges){ +        for(const range_t &range:  ranges){              for(uint16_t addr = range.first; addr <= range.second; addr++){                  this->send_reg(addr);              } diff --git a/host/lib/usrp/b100/codec_ctrl.cpp b/host/lib/usrp/b100/codec_ctrl.cpp index e78608beb..01fd51f52 100644 --- a/host/lib/usrp/b100/codec_ctrl.cpp +++ b/host/lib/usrp/b100/codec_ctrl.cpp @@ -259,7 +259,7 @@ void b100_codec_ctrl_impl::write_aux_dac(aux_dac_t which, double volts){   **********************************************************************/  void b100_codec_ctrl_impl::send_reg(uint8_t addr){      uint32_t reg = _ad9862_regs.get_write_reg(addr); -    UHD_LOGV(rarely) << "codec control write reg: " << std::hex << reg << std::endl; +    UHD_LOGGER_TRACE("B100") << "codec control write reg: " << std::hex << reg ;      _iface->transact_spi(          B100_SPI_SS_AD9862,          spi_config_t::EDGE_RISE, @@ -269,13 +269,13 @@ void b100_codec_ctrl_impl::send_reg(uint8_t addr){  void b100_codec_ctrl_impl::recv_reg(uint8_t addr){      uint32_t reg = _ad9862_regs.get_read_reg(addr); -    UHD_LOGV(rarely) << "codec control read reg: " << std::hex << reg << std::endl; +    UHD_LOGGER_TRACE("B100") << "codec control read reg: " << std::hex << reg ;      uint32_t ret = _iface->transact_spi(          B100_SPI_SS_AD9862,          spi_config_t::EDGE_RISE,          reg, 16, true /*rb*/      ); -    UHD_LOGV(rarely) << "codec control read ret: " << std::hex << uint16_t(ret & 0xFF) << std::endl; +    UHD_LOGGER_TRACE("B100") << "codec control read ret: " << std::hex << uint16_t(ret & 0xFF) ;      _ad9862_regs.set_reg(addr, uint8_t(ret&0xff));  } diff --git a/host/lib/usrp/b100/io_impl.cpp b/host/lib/usrp/b100/io_impl.cpp index c1810ed8c..7cccc7752 100644 --- a/host/lib/usrp/b100/io_impl.cpp +++ b/host/lib/usrp/b100/io_impl.cpp @@ -23,7 +23,7 @@  #include <boost/format.hpp>  #include <boost/bind.hpp>  #include <boost/thread.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/utils/log.hpp>  #include <boost/make_shared.hpp> @@ -36,10 +36,10 @@ void b100_impl::update_rates(void){      _tree->access<double>(mb_path / "tick_rate").update();      //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")){ +    for(const std::string &name:  _tree->list(mb_path / "rx_dsps")){          _tree->access<double>(mb_path / "rx_dsps" / name / "rate" / "value").update();      } -    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +    for(const std::string &name:  _tree->list(mb_path / "tx_dsps")){          _tree->access<double>(mb_path / "tx_dsps" / name / "rate" / "value").update();      }  } diff --git a/host/lib/usrp/b100/usb_zero_copy_wrapper.cpp b/host/lib/usrp/b100/usb_zero_copy_wrapper.cpp index d57d57f21..ea3e9f87e 100644 --- a/host/lib/usrp/b100/usb_zero_copy_wrapper.cpp +++ b/host/lib/usrp/b100/usb_zero_copy_wrapper.cpp @@ -18,10 +18,9 @@  #include <uhd/transport/usb_zero_copy.hpp>  #include <uhd/transport/buffer_pool.hpp>  #include <uhd/utils/byteswap.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/tasks.hpp>  #include <uhd/utils/atomic.hpp> -#include <boost/foreach.hpp>  #include <boost/make_shared.hpp>  #include <boost/thread/mutex.hpp>  #include <boost/thread/condition_variable.hpp> diff --git a/host/lib/usrp/b200/b200_iface.cpp b/host/lib/usrp/b200/b200_iface.cpp index 6f9bdd330..81752b28f 100644 --- a/host/lib/usrp/b200/b200_iface.cpp +++ b/host/lib/usrp/b200/b200_iface.cpp @@ -19,7 +19,7 @@  #include "../../utils/ihex.hpp"  #include <uhd/config.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/utils/log.hpp>  #include <uhd/exception.hpp>  #include <boost/functional/hash.hpp> @@ -212,7 +212,7 @@ public:      void load_firmware(const std::string filestring, UHD_UNUSED(bool force) = false)      {          if (load_img_msg) -            UHD_MSG(status) << "Loading firmware image: " +            UHD_LOGGER_INFO("B200") << "Loading firmware image: "                              << filestring << "..." << std::flush;          ihex_reader file_reader(filestring); @@ -227,7 +227,7 @@ public:              throw uhd::io_error(str(boost::format("Could not load firmware: \n%s") % e.what()));          } -        UHD_MSG(status) << std::endl; +        UHD_LOGGER_INFO("B200") ;          //TODO          //usrp_set_firmware_hash(hash); //set hash before reset @@ -446,7 +446,7 @@ public:              wait_count++;          } while(fx3_state != FX3_STATE_FPGA_READY); -        if (load_img_msg) UHD_MSG(status) << "Loading FPGA image: " \ +        if (load_img_msg) UHD_LOGGER_INFO("B200") << "Loading FPGA image: " \              << filestring << "..." << std::flush;          bytes_to_xfer = 1; @@ -487,13 +487,13 @@ public:              if (load_img_msg)              { -                if (bytes_sent == 0) UHD_MSG(status) << "  0%" << std::flush; +                if (bytes_sent == 0) UHD_LOGGER_INFO("B200") << "  0%" << std::flush;                  const size_t percent_before = size_t((bytes_sent*100)/file_size);                  bytes_sent += transfer_count;                  const size_t percent_after = size_t((bytes_sent*100)/file_size);                  if (percent_before != percent_after)                  { -                    UHD_MSG(status) << "\b\b\b\b" << std::setw(3) << percent_after << "%" << std::flush; +                    UHD_LOGGER_INFO("B200") << "\b\b\b\b" << std::setw(3) << percent_after << "%" << std::flush;                  }              }          } @@ -516,7 +516,7 @@ public:          usrp_set_fpga_hash(hash);          if (load_img_msg) -            UHD_MSG(status) << "\b\b\b\b done" << std::endl; +            UHD_LOGGER_INFO("B200") << "\b\b\b\b done" ;          return 0;      } diff --git a/host/lib/usrp/b200/b200_image_loader.cpp b/host/lib/usrp/b200/b200_image_loader.cpp index b9c2c0caf..af79a59fc 100644 --- a/host/lib/usrp/b200/b200_image_loader.cpp +++ b/host/lib/usrp/b200/b200_image_loader.cpp @@ -16,7 +16,6 @@  //  #include <boost/assign.hpp> -#include <boost/foreach.hpp>  #include <boost/lexical_cast.hpp>  #include <uhd/exception.hpp> @@ -45,7 +44,7 @@ static b200_iface::sptr get_b200_iface(const image_loader::image_loader_args_t&      mboard_eeprom_t eeprom; // Internal use      if(dev_handles.size() > 0){ -        BOOST_FOREACH(usb_device_handle::sptr dev_handle, dev_handles){ +        for(usb_device_handle::sptr dev_handle:  dev_handles){              if(dev_handle->firmware_loaded()){                  iface = b200_iface::make(usb_control::make(dev_handle,0));                  eeprom = mboard_eeprom_t(*iface, "B200"); @@ -74,7 +73,7 @@ static b200_iface::sptr get_b200_iface(const image_loader::image_loader_args_t&              std::string err_msg = "Could not resolve given args to a single B2XX device.\n"                                    "Applicable devices:\n"; -            BOOST_FOREACH(usb_device_handle::sptr dev_handle, applicable_dev_handles){ +            for(usb_device_handle::sptr dev_handle:  applicable_dev_handles){                  eeprom = mboard_eeprom_t(*b200_iface::make(usb_control::make(dev_handle,0)), "B200");                  err_msg += str(boost::format(" * %s (serial=%s)\n")                                 % B2XX_STR_NAMES.get(get_b200_product(dev_handle, mb_eeprom), "B2XX") diff --git a/host/lib/usrp/b200/b200_impl.cpp b/host/lib/usrp/b200/b200_impl.cpp index e2a0e0b70..a513e1336 100644 --- a/host/lib/usrp/b200/b200_impl.cpp +++ b/host/lib/usrp/b200/b200_impl.cpp @@ -19,7 +19,7 @@  #include "b200_regs.hpp"  #include <uhd/config.hpp>  #include <uhd/transport/usb_control.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/cast.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/static.hpp> @@ -60,7 +60,7 @@ public:          }      }      clocking_mode_t get_clocking_mode() { -        return AD9361_XTAL_N_CLK_PATH; +        return clocking_mode_t::AD9361_XTAL_N_CLK_PATH;      }      digital_interface_mode_t get_digital_interface_mode() {          return AD9361_DDR_FDD_LVCMOS; @@ -88,7 +88,7 @@ public:          }      }      clocking_mode_t get_clocking_mode() { -        return AD9361_XTAL_N_CLK_PATH; +        return clocking_mode_t::AD9361_XTAL_N_CLK_PATH;      }      digital_interface_mode_t get_digital_interface_mode() {          return AD9361_DDR_FDD_LVCMOS; @@ -172,7 +172,7 @@ static device_addrs_t b200_find(const device_addr_t &hint)      //Return an empty list of addresses when an address or resource is specified,      //since an address and resource is intended for a different, non-USB, device. -    BOOST_FOREACH(device_addr_t hint_i, separate_device_addr(hint)) { +    for(device_addr_t hint_i:  separate_device_addr(hint)) {          if (hint_i.has_key("addr") || hint_i.has_key("resource")) return b200_addrs;      } @@ -182,7 +182,7 @@ static device_addrs_t b200_find(const device_addr_t &hint)      // so that re-enumeration after fw load can occur successfully.      // This requirement is a courtesy of libusb1.0 on windows.      size_t found = 0; -    BOOST_FOREACH(usb_device_handle::sptr handle, get_b200_device_handles(hint)) { +    for(usb_device_handle::sptr handle:  get_b200_device_handles(hint)) {          //extract the firmware path for the b200          std::string b200_fw_image;          try{ @@ -190,10 +190,10 @@ static device_addrs_t b200_find(const device_addr_t &hint)              b200_fw_image = uhd::find_image_path(b200_fw_image, STR(UHD_IMAGES_DIR)); // FIXME          }          catch(uhd::exception &e){ -            UHD_MSG(warning) << e.what(); +            UHD_LOGGER_WARNING("B200") << e.what();              return b200_addrs;          } -        UHD_LOG << "the firmware image: " << b200_fw_image << std::endl; +        UHD_LOGGER_DEBUG("B200") << "the firmware image: " << b200_fw_image ;          usb_control::sptr control;          try{control = usb_control::make(handle, 0);} @@ -213,7 +213,7 @@ static device_addrs_t b200_find(const device_addr_t &hint)      //search for the device until found or timeout      while (boost::get_system_time() < timeout_time and b200_addrs.empty() and found != 0)      { -        BOOST_FOREACH(usb_device_handle::sptr handle, get_b200_device_handles(hint)) +        for(usb_device_handle::sptr handle:  get_b200_device_handles(hint))          {              usb_control::sptr control;              try{control = usb_control::make(handle, 0);} @@ -261,7 +261,7 @@ static device::sptr b200_make(const device_addr_t &device_addr)          return device::sptr(new b200_impl(device_addr, handle));      }      catch (const uhd::usb_error &) { -        UHD_MSG(status) << "Detected bad USB state; resetting." << std::endl; +        UHD_LOGGER_INFO("B200") << "Detected bad USB state; resetting." ;          libusb::device_handle::sptr dev_handle(libusb::device_handle::get_cached_handle(              boost::static_pointer_cast<libusb::special_handle>(handle)->get_device()          )); @@ -344,7 +344,7 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s      std::vector<usb_device_handle::sptr> device_list = usb_device_handle::get_device_list(vid_pid_pair_list);      //locate the matching handle in the device list -    BOOST_FOREACH(usb_device_handle::sptr dev_handle, device_list) { +    for(usb_device_handle::sptr dev_handle:  device_list) {          try {              if (dev_handle->get_serial() == device_addr["serial"]){                  handle = dev_handle; @@ -390,7 +390,7 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s          _revision = boost::lexical_cast<size_t>(mb_eeprom["revision"]);      } -    UHD_MSG(status) << "Detected Device: " << B2XX_STR_NAMES[_product] << std::endl; +    UHD_LOGGER_INFO("B200") << "Detected Device: " << B2XX_STR_NAMES[_product] ;      _gpsdo_capable = (not (_product == B200MINI or _product == B205MINI)); @@ -437,7 +437,7 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s      // Create control transport      ////////////////////////////////////////////////////////////////////      uint8_t usb_speed = _iface->get_usb_speed(); -    UHD_MSG(status) << "Operating over USB " << (int) usb_speed << "." << std::endl; +    UHD_LOGGER_INFO("B200") << "Operating over USB " << (int) usb_speed << "." ;      const std::string min_frame_size = (usb_speed == 3) ? "1024" : "512";      device_addr_t ctrl_xport_args; @@ -488,19 +488,18 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s          if ((_local_ctrl->peek32(RB32_CORE_STATUS) & 0xff) != B200_GPSDO_ST_NONE)          { -            UHD_MSG(status) << "Detecting internal GPSDO.... " << std::flush; +            UHD_LOGGER_INFO("B200") << "Detecting internal GPSDO.... " << std::flush;              try              {                  _gps = gps_ctrl::make(_async_task_data->gpsdo_uart);              }              catch(std::exception &e)              { -                UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl; +                UHD_LOGGER_ERROR("B200") << "An error occurred making GPSDO control: " << e.what();              }              if (_gps and _gps->gps_detected())              { -                //UHD_MSG(status) << "found" << std::endl; -                BOOST_FOREACH(const std::string &name, _gps->get_sensors()) +                for(const std::string &name:  _gps->get_sensors())                  {                      _tree->create<sensor_value_t>(mb_path / "sensors" / name)                          .set_publisher(boost::bind(&gps_ctrl::get_sensor, _gps, name)); @@ -553,7 +552,7 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s      ////////////////////////////////////////////////////////////////////      // Init codec - turns on clocks      //////////////////////////////////////////////////////////////////// -    UHD_MSG(status) << "Initialize CODEC control..." << std::endl; +    UHD_LOGGER_INFO("B200") << "Initialize CODEC control..." ;      ad9361_params::sptr client_settings;      if (_product == B200MINI or _product == B205MINI) {          client_settings = boost::make_shared<b2xxmini_ad9361_client_t>(); @@ -610,7 +609,7 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s      ////////////////////////////////////////////////////////////////////      // setup radio control      //////////////////////////////////////////////////////////////////// -    UHD_MSG(status) << "Initialize Radio control..." << std::endl; +    UHD_LOGGER_INFO("B200") << "Initialize Radio control..." ;      const size_t num_radio_chains = ((_local_ctrl->peek32(RB32_CORE_STATUS) >> 8) & 0xff);      UHD_ASSERT_THROW(num_radio_chains > 0);      UHD_ASSERT_THROW(num_radio_chains <= 2); @@ -621,7 +620,7 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s          this->setup_radio(i);      //now test each radio module's connection to the codec interface -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          _codec_mgr->loopback_self_test(              boost::bind( @@ -641,7 +640,7 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s          .add_coerced_subscriber(boost::bind(&b200_impl::sync_times, this));      _tree->create<time_spec_t>(mb_path / "time" / "pps")          .set_publisher(boost::bind(&time_core_3000::get_time_last_pps, _radio_perifs[0].time64)); -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          _tree->access<time_spec_t>(mb_path / "time" / "pps")              .add_coerced_subscriber(boost::bind(&time_core_3000::set_time_next_pps, perif.time64, _1)); @@ -670,7 +669,7 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s      // front panel gpio      ////////////////////////////////////////////////////////////////////      _radio_perifs[0].fp_gpio = gpio_atr_3000::make(_radio_perifs[0].ctrl, TOREG(SR_FP_GPIO), RB32_FP_GPIO); -    BOOST_FOREACH(const gpio_attr_map_t::value_type attr, gpio_attr_map) +    for(const gpio_attr_map_t::value_type attr:  gpio_attr_map)      {              _tree->create<uint32_t>(mb_path / "gpio" / "FP0" / attr.second)              .set(0) @@ -692,7 +691,7 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s      ////////////////////////////////////////////////////////////////////      // Init the clock rate and the auto mcr appropriately      if (not device_addr.has_key("master_clock_rate")) { -        UHD_MSG(status) << "Setting master clock rate selection to 'automatic'." << std::endl; +        UHD_LOGGER_INFO("B200") << "Setting master clock rate selection to 'automatic'." ;      }      // We can automatically choose a master clock rate, but not if the user specifies one      const double default_tick_rate = device_addr.cast<double>("master_clock_rate", ad936x_manager::DEFAULT_TICK_RATE); @@ -701,11 +700,11 @@ b200_impl::b200_impl(const uhd::device_addr_t& device_addr, usb_device_handle::s      //subdev spec contains full width of selections      subdev_spec_t rx_spec, tx_spec; -    BOOST_FOREACH(const std::string &fe, _tree->list(mb_path / "dboards" / "A" / "rx_frontends")) +    for(const std::string &fe:  _tree->list(mb_path / "dboards" / "A" / "rx_frontends"))      {          rx_spec.push_back(subdev_spec_pair_t("A", fe));      } -    BOOST_FOREACH(const std::string &fe, _tree->list(mb_path / "dboards" / "A" / "tx_frontends")) +    for(const std::string &fe:  _tree->list(mb_path / "dboards" / "A" / "tx_frontends"))      {          tx_spec.push_back(subdev_spec_pair_t("A", fe));      } @@ -830,7 +829,7 @@ void b200_impl::setup_radio(const size_t dspno)      // create RF frontend interfacing      ////////////////////////////////////////////////////////////////////      static const std::vector<direction_t> dirs = boost::assign::list_of(RX_DIRECTION)(TX_DIRECTION); -    BOOST_FOREACH(direction_t dir, dirs) { +    for(direction_t dir:  dirs) {          const std::string x = (dir == RX_DIRECTION) ? "rx" : "tx";          const std::string key = std::string(((dir == RX_DIRECTION) ? "RX" : "TX")) + std::string(((dspno == _fe1) ? "1" : "2"));          const fs_path rf_fe_path @@ -874,7 +873,7 @@ void b200_impl::setup_radio(const size_t dspno)  void b200_impl::register_loopback_self_test(wb_iface::sptr iface)  {      bool test_fail = false; -    UHD_MSG(status) << "Performing register loopback test... " << std::flush; +    UHD_LOGGER_INFO("B200") << "Performing register loopback test... " << std::flush;      size_t hash = size_t(time(NULL));      for (size_t i = 0; i < 100; i++)      { @@ -883,7 +882,7 @@ void b200_impl::register_loopback_self_test(wb_iface::sptr iface)          test_fail = iface->peek32(RB32_TEST) != uint32_t(hash);          if (test_fail) break; //exit loop on any failure      } -    UHD_MSG(status) << ((test_fail)? "fail" : "pass") << std::endl; +    UHD_LOGGER_INFO("B200") << ((test_fail)? "fail" : "pass") ;  }  /*********************************************************************** @@ -919,20 +918,20 @@ void b200_impl::enforce_tick_rate_limits(size_t chan_count, double tick_rate, co  double b200_impl::set_tick_rate(const double new_tick_rate)  { -    UHD_MSG(status) << (boost::format("Asking for clock rate %.6f MHz... ") % (new_tick_rate/1e6)) << std::flush; +    UHD_LOGGER_INFO("B200") << (boost::format("Asking for clock rate %.6f MHz... ") % (new_tick_rate/1e6)) << std::flush;      check_tick_rate_with_current_streamers(new_tick_rate);   // Defined in b200_io_impl.cpp      // Make sure the clock rate is actually changed before doing      // the full Monty of setting regs and loopback tests etc.      if (std::abs(new_tick_rate - _tick_rate) < 1.0) { -        UHD_MSG(status) << "OK" << std::endl; +        UHD_LOGGER_INFO("B200") << "OK" ;          return _tick_rate;      }      _tick_rate = _codec_ctrl->set_clock_rate(new_tick_rate); -    UHD_MSG(status) << std::endl << (boost::format("Actually got clock rate %.6f MHz.") % (_tick_rate/1e6)) << std::endl; +    UHD_LOGGER_INFO("B200")  << (boost::format("Actually got clock rate %.6f MHz.") % (_tick_rate/1e6)) ; -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          perif.time64->set_tick_rate(_tick_rate);          perif.time64->self_test(); @@ -1088,7 +1087,7 @@ void b200_impl::update_time_source(const std::string &source)  void b200_impl::set_time(const uhd::time_spec_t& t)  { -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)          perif.time64->set_time_sync(t);      _local_ctrl->poke32(TOREG(SR_CORE_SYNC), 1 << 2 | uint32_t(_time_source));      _local_ctrl->poke32(TOREG(SR_CORE_SYNC), _time_source); diff --git a/host/lib/usrp/b200/b200_io_impl.cpp b/host/lib/usrp/b200/b200_io_impl.cpp index 0a00b9402..7366b06f5 100644 --- a/host/lib/usrp/b200/b200_io_impl.cpp +++ b/host/lib/usrp/b200/b200_io_impl.cpp @@ -45,7 +45,7 @@ void b200_impl::check_tick_rate_with_current_streamers(double rate)  size_t b200_impl::max_chan_count(const std::string &direction /* = "" */)  {      size_t max_count = 0; -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          if ((direction == "RX" or direction.empty()) and not perif.rx_streamer.expired()) {              boost::shared_ptr<sph::recv_packet_streamer> rx_streamer = @@ -97,7 +97,7 @@ void b200_impl::set_auto_tick_rate(      for (int i = 0; i < 2; i++) { // Loop through rx and tx          std::string dir = (i == 0) ? "tx" : "rx";          // We assume all 'set' DSPs are being used. -        BOOST_FOREACH(const std::string &dsp_no, _tree->list(str(boost::format("/mboards/0/%s_dsps") % dir))) { +        for(const std::string &dsp_no:  _tree->list(str(boost::format("/mboards/0/%s_dsps") % dir))) {              fs_path dsp_path = str(boost::format("/mboards/0/%s_dsps/%s") % dir % dsp_no);              if (dsp_path == tree_dsp_path) {                  continue; @@ -135,9 +135,9 @@ void b200_impl::set_auto_tick_rate(              _tree->access<double>("/mboards/0/tick_rate").set(new_rate);          }      } catch (const uhd::value_error &) { -        UHD_MSG(warning) -            << "Cannot automatically determine an appropriate tick rate for these sampling rates." << std::endl -            << "Consider using different sampling rates, or manually specify a suitable master clock rate." << std::endl; +        UHD_LOGGER_WARNING("B200") +            << "Cannot automatically determine an appropriate tick rate for these sampling rates."  +            << "Consider using different sampling rates, or manually specify a suitable master clock rate." ;          return; // Let the others handle this      }  } @@ -146,14 +146,14 @@ void b200_impl::update_tick_rate(const double new_tick_rate)  {      check_tick_rate_with_current_streamers(new_tick_rate); -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          boost::shared_ptr<sph::recv_packet_streamer> my_streamer =              boost::dynamic_pointer_cast<sph::recv_packet_streamer>(perif.rx_streamer.lock());          if (my_streamer) my_streamer->set_tick_rate(new_tick_rate);          perif.framer->set_tick_rate(new_tick_rate);      } -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          boost::shared_ptr<sph::send_packet_streamer> my_streamer =              boost::dynamic_pointer_cast<sph::send_packet_streamer>(perif.tx_streamer.lock()); @@ -356,7 +356,7 @@ boost::optional<uhd::msg_task::msg_type_t> b200_impl::handle_async_task(          }          catch(const std::exception &ex)          { -            UHD_MSG(error) << "Error parsing ctrl packet: " << ex.what() << std::endl; +            UHD_LOGGER_ERROR("B200") << "Error parsing ctrl packet: " << ex.what();              break;          } @@ -370,7 +370,7 @@ boost::optional<uhd::msg_task::msg_type_t> b200_impl::handle_async_task(      //doh!      default: -        UHD_MSG(error) << "Got a ctrl packet with unknown SID " << sid << std::endl; +        UHD_LOGGER_ERROR("B200") << "Got a ctrl packet with unknown SID " << sid;      }      return boost::none;  } diff --git a/host/lib/usrp/b200/b200_uart.cpp b/host/lib/usrp/b200/b200_uart.cpp index 3c49ebf2a..143600c51 100644 --- a/host/lib/usrp/b200/b200_uart.cpp +++ b/host/lib/usrp/b200/b200_uart.cpp @@ -20,10 +20,9 @@  #include <uhd/transport/bounded_buffer.hpp>  #include <uhd/transport/vrt_if_packet.hpp>  #include <uhd/utils/byteswap.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/types/time_spec.hpp>  #include <uhd/exception.hpp> -#include <boost/foreach.hpp>  using namespace uhd;  using namespace uhd::transport; @@ -69,7 +68,7 @@ struct b200_uart_impl : b200_uart      void write_uart(const std::string &buff)      { -        BOOST_FOREACH(const char ch, buff) +        for(const char ch:  buff)          {              this->send_char(ch);          } diff --git a/host/lib/usrp/common/CMakeLists.txt b/host/lib/usrp/common/CMakeLists.txt index 9f4cf09b5..9480d0284 100644 --- a/host/lib/usrp/common/CMakeLists.txt +++ b/host/lib/usrp/common/CMakeLists.txt @@ -38,5 +38,4 @@ LIBUHD_APPEND_SOURCES(      ${CMAKE_CURRENT_SOURCE_DIR}/validate_subdev_spec.cpp      ${CMAKE_CURRENT_SOURCE_DIR}/recv_packet_demuxer.cpp      ${CMAKE_CURRENT_SOURCE_DIR}/fifo_ctrl_excelsior.cpp -    ${CMAKE_CURRENT_SOURCE_DIR}/usrp3_fw_ctrl_iface.cpp  ) diff --git a/host/lib/usrp/common/ad9361_ctrl.cpp b/host/lib/usrp/common/ad9361_ctrl.cpp index 0dc5e7919..a1c158eae 100644 --- a/host/lib/usrp/common/ad9361_ctrl.cpp +++ b/host/lib/usrp/common/ad9361_ctrl.cpp @@ -17,7 +17,7 @@  #include "ad9361_ctrl.hpp"  #include <uhd/types/ranges.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/types/serial.hpp>  #include <cstring>  #include <boost/format.hpp> @@ -153,10 +153,10 @@ public:          const double clipped_rate = clock_rate_range.clip(rate);          if (clipped_rate != rate) { -            UHD_MSG(warning) << boost::format( +            UHD_LOGGER_WARNING("AD936X") << boost::format(                      "The requested master_clock_rate %f MHz exceeds bounds imposed by UHD.\n"                      "The master_clock_rate has been forced to %f MHz.\n" -            ) % (rate/1e6) % (clipped_rate/1e6) << std::endl; +            ) % (rate/1e6) % (clipped_rate/1e6) ;          }          double return_rate = _device.set_clock_rate(clipped_rate); diff --git a/host/lib/usrp/common/ad9361_driver/ad9361_client.h b/host/lib/usrp/common/ad9361_driver/ad9361_client.h index 921045fbd..4fea53521 100644 --- a/host/lib/usrp/common/ad9361_driver/ad9361_client.h +++ b/host/lib/usrp/common/ad9361_driver/ad9361_client.h @@ -34,10 +34,10 @@ typedef enum {  /*!   * Clocking mode   */ -typedef enum { +enum class clocking_mode_t {      AD9361_XTAL_P_CLK_PATH,      AD9361_XTAL_N_CLK_PATH -} clocking_mode_t; +};  /*!   * Digital interface specific diff --git a/host/lib/usrp/common/ad9361_driver/ad9361_device.cpp b/host/lib/usrp/common/ad9361_driver/ad9361_device.cpp index e2ed2c77d..da0ab0b9a 100644 --- a/host/lib/usrp/common/ad9361_driver/ad9361_device.cpp +++ b/host/lib/usrp/common/ad9361_driver/ad9361_device.cpp @@ -24,7 +24,7 @@  #include <cmath>  #include <uhd/exception.hpp>  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> +  #include <stdint.h>  #include <boost/date_time/posix_time/posix_time.hpp>  #include <boost/thread/thread.hpp> @@ -321,7 +321,7 @@ double ad9361_device_t::_calibrate_baseband_rx_analog_filter(double req_rfbw)      double bbbw = req_rfbw / 2.0;      if(bbbw > _baseband_bw / 2.0)      { -        UHD_LOG << "baseband bandwidth too large for current sample rate. Setting bandwidth to: "<<_baseband_bw; +        UHD_LOGGER_DEBUG("AD936X")<< "baseband bandwidth too large for current sample rate. Setting bandwidth to: "<<_baseband_bw;          bbbw = _baseband_bw / 2.0;      } @@ -388,7 +388,7 @@ double ad9361_device_t::_calibrate_baseband_tx_analog_filter(double req_rfbw)      if(bbbw > _baseband_bw / 2.0)      { -        UHD_LOG << "baseband bandwidth too large for current sample rate. Setting bandwidth to: "<<_baseband_bw; +        UHD_LOGGER_DEBUG("AD936X")<< "baseband bandwidth too large for current sample rate. Setting bandwidth to: "<<_baseband_bw;          bbbw = _baseband_bw / 2.0;      } @@ -443,7 +443,7 @@ double ad9361_device_t::_calibrate_secondary_tx_filter(double req_rfbw)      if(bbbw > _baseband_bw / 2.0)      { -        UHD_LOG << "baseband bandwidth too large for current sample rate. Setting bandwidth to: "<<_baseband_bw; +        UHD_LOGGER_DEBUG("AD936X")<< "baseband bandwidth too large for current sample rate. Setting bandwidth to: "<<_baseband_bw;          bbbw = _baseband_bw / 2.0;      } @@ -539,7 +539,7 @@ double ad9361_device_t::_calibrate_rx_TIAs(double req_rfbw)      if(bbbw > _baseband_bw / 2.0)      { -        UHD_LOG << "baseband bandwidth too large for current sample rate. Setting bandwidth to: "<<_baseband_bw; +        UHD_LOGGER_DEBUG("AD936X")<< "baseband bandwidth too large for current sample rate. Setting bandwidth to: "<<_baseband_bw;          bbbw = _baseband_bw / 2.0;      } @@ -1169,7 +1169,7 @@ void ad9361_device_t::_setup_synth(direction_t direction, double vcorate)   * fed to the public set_clock_rate function. */  double ad9361_device_t::_tune_bbvco(const double rate)  { -    UHD_LOG << boost::format("[ad9361_device_t::_tune_bbvco] rate=%.10f\n") % rate; +    UHD_LOGGER_TRACE("AD936X")<< boost::format("[ad9361_device_t::_tune_bbvco] rate=%.10f\n") % rate;      /* Let's not re-tune to the same frequency over and over... */      if (freq_is_nearly_equal(rate, _req_coreclk)) { @@ -1197,13 +1197,13 @@ double ad9361_device_t::_tune_bbvco(const double rate)      if (i == 7)          throw uhd::runtime_error("[ad9361_device_t] _tune_bbvco: wrong vcorate"); -    UHD_LOG << boost::format("[ad9361_device_t::_tune_bbvco] vcodiv=%d vcorate=%.10f\n") % vcodiv % vcorate; +    UHD_LOGGER_TRACE("AD936X")<< boost::format("[ad9361_device_t::_tune_bbvco] vcodiv=%d vcorate=%.10f\n") % vcodiv % vcorate;      /* Fo = Fref * (Nint + Nfrac / mod) */      int nint = static_cast<int>(vcorate / fref); -    UHD_LOG << boost::format("[ad9361_device_t::_tune_bbvco] (nint)=%.10f\n") % (vcorate / fref); +    UHD_LOGGER_TRACE("AD936X")<< boost::format("[ad9361_device_t::_tune_bbvco] (nint)=%.10f\n") % (vcorate / fref);      int nfrac = static_cast<int>(boost::math::round(((vcorate / fref) - (double) nint) * (double) modulus)); -    UHD_LOG << boost::format("[ad9361_device_t::_tune_bbvco] (nfrac)=%.10f\n") % (((vcorate / fref) - (double) nint) * (double) modulus); -    UHD_LOG << boost::format("[ad9361_device_t::_tune_bbvco] nint=%d nfrac=%d\n") % nint % nfrac; +    UHD_LOGGER_TRACE("AD936X")<< boost::format("[ad9361_device_t::_tune_bbvco] (nfrac)=%.10f\n") % (((vcorate / fref) - (double) nint) * (double) modulus); +    UHD_LOGGER_TRACE("AD936X")<< boost::format("[ad9361_device_t::_tune_bbvco] nint=%d nfrac=%d\n") % nint % nfrac;      double actual_vcorate = fref              * ((double) nint + ((double) nfrac / (double) modulus)); @@ -1381,7 +1381,7 @@ double ad9361_device_t::_setup_rates(const double rate)      /* If we make it into this function, then we are tuning to a new rate.       * Store the new rate. */      _req_clock_rate = rate; -    UHD_LOG << boost::format("[ad9361_device_t::_setup_rates] rate=%.6d\n") % rate; +    UHD_LOGGER_TRACE("AD936X")<< boost::format("[ad9361_device_t::_setup_rates] rate=%.6d\n") % rate;      /* Set the decimation and interpolation values in the RX and TX chains.       * This also switches filters in / out. Note that all transmitters and @@ -1467,7 +1467,7 @@ double ad9361_device_t::_setup_rates(const double rate)          throw uhd::runtime_error("[ad9361_device_t] [_setup_rates] INVALID_CODE_PATH");      } -    UHD_LOG << boost::format("[ad9361_device_t::_setup_rates] divfactor=%d\n") % divfactor; +    UHD_LOGGER_TRACE("AD936X")<< boost::format("[ad9361_device_t::_setup_rates] divfactor=%d\n") % divfactor;      /* Tune the BBPLL to get the ADC and DAC clocks. */      const double adcclk = _tune_bbvco(rate * divfactor); @@ -1489,7 +1489,7 @@ double ad9361_device_t::_setup_rates(const double rate)      _io_iface->poke8(0x004, _regs.inputsel);      _io_iface->poke8(0x00A, _regs.bbpll); -    UHD_LOG << boost::format("[ad9361_device_t::_setup_rates] adcclk=%f\n") % adcclk; +    UHD_LOGGER_TRACE("AD936X")<< boost::format("[ad9361_device_t::_setup_rates] adcclk=%f\n") % adcclk;      _baseband_bw = (adcclk / divfactor);      /* @@ -1583,11 +1583,11 @@ void ad9361_device_t::initialize()      /* Enable clocks. */      switch (_client_params->get_clocking_mode()) { -    case AD9361_XTAL_N_CLK_PATH: { +    case clocking_mode_t::AD9361_XTAL_N_CLK_PATH: {          _io_iface->poke8(0x009, 0x17);      } break; -    case AD9361_XTAL_P_CLK_PATH: { +    case clocking_mode_t::AD9361_XTAL_P_CLK_PATH: {          _io_iface->poke8(0x009, 0x07);          _io_iface->poke8(0x292, 0x08);          _io_iface->poke8(0x293, 0x80); @@ -1798,7 +1798,7 @@ double ad9361_device_t::set_clock_rate(const double req_rate)          throw uhd::runtime_error("[ad9361_device_t] Requested master clock rate outside range");      } -    UHD_LOG << boost::format("[ad9361_device_t::set_clock_rate] req_rate=%.10f\n") % req_rate; +    UHD_LOGGER_TRACE("AD936X")<< boost::format("[ad9361_device_t::set_clock_rate] req_rate=%.10f\n") % req_rate;      /* UHD has a habit of requesting the same rate like four times when it       * starts up. This prevents that, and any bugs in user code that request @@ -1840,7 +1840,7 @@ double ad9361_device_t::set_clock_rate(const double req_rate)       * all the hard work gets done. */      double rate = _setup_rates(req_rate); -    UHD_LOG << boost::format("[ad9361_device_t::set_clock_rate] rate=%.10f\n") % rate; +    UHD_LOGGER_TRACE("AD936X")<< boost::format("[ad9361_device_t::set_clock_rate] rate=%.10f\n") % rate;      /* Transition to the ALERT state and calibrate everything. */      _io_iface->poke8(0x015, 0x04); //dual synth mode, synth en ctrl en diff --git a/host/lib/usrp/common/ad936x_manager.cpp b/host/lib/usrp/common/ad936x_manager.cpp index 2b6d69c15..503678554 100644 --- a/host/lib/usrp/common/ad936x_manager.cpp +++ b/host/lib/usrp/common/ad936x_manager.cpp @@ -16,8 +16,7 @@  //  #include "ad936x_manager.hpp" -#include <uhd/utils/msg.hpp> -#include <boost/foreach.hpp> +#include <uhd/utils/log.hpp>  #include <boost/functional/hash.hpp>  #include <boost/thread/thread.hpp> @@ -66,7 +65,7 @@ class ad936x_manager_impl : public ad936x_manager       ***********************************************************************/      void init_codec()      { -        BOOST_FOREACH(const std::string &rx_fe, _rx_frontends) { +        for(const std::string &rx_fe:  _rx_frontends) {              _codec_ctrl->set_gain(rx_fe, DEFAULT_GAIN);              _codec_ctrl->set_bw_filter(rx_fe, DEFAULT_BANDWIDTH);              _codec_ctrl->tune(rx_fe, DEFAULT_FREQ); @@ -74,7 +73,7 @@ class ad936x_manager_impl : public ad936x_manager              _codec_ctrl->set_iq_balance_auto(rx_fe, DEFAULT_AUTO_IQ_BALANCE);              _codec_ctrl->set_agc(rx_fe, DEFAULT_AGC_ENABLE);          } -        BOOST_FOREACH(const std::string &tx_fe, _tx_frontends) { +        for(const std::string &tx_fe:  _tx_frontends) {              _codec_ctrl->set_gain(tx_fe, DEFAULT_GAIN);              _codec_ctrl->set_bw_filter(tx_fe, DEFAULT_BANDWIDTH);              _codec_ctrl->tune(tx_fe, DEFAULT_FREQ); @@ -98,7 +97,7 @@ class ad936x_manager_impl : public ad936x_manager      ) {          // Put AD936x in loopback mode          _codec_ctrl->data_port_loopback(true); -        UHD_MSG(status) << "Performing CODEC loopback test... " << std::flush; +        UHD_LOGGER_INFO("AD936X") << "Performing CODEC loopback test... ";          size_t hash = size_t(time(NULL));          // Allow some time for AD936x to enter loopback mode. @@ -127,11 +126,11 @@ class ad936x_manager_impl : public ad936x_manager              bool test_fail = word32 != rb_tx or word32 != rb_rx;              if(test_fail)              { -                UHD_MSG(status) << "fail" << std::endl; +                UHD_LOGGER_INFO("AD936X") << "CODEC loopback test failed";                  throw uhd::runtime_error("CODEC loopback test failed.");              }          } -        UHD_MSG(status) << "pass" << std::endl; +        UHD_LOGGER_INFO("AD936X") << "CODEC loopback test passed";          // Zero out the idle data.          poker_functor(0); @@ -194,10 +193,10 @@ class ad936x_manager_impl : public ad936x_manager      bool check_bandwidth(double rate, const std::string dir)      {          if (rate > _codec_ctrl->get_bw_filter_range(dir).stop()) { -            UHD_MSG(warning) +            UHD_LOGGER_WARNING("AD936X")                  << "Selected " << dir << " bandwidth (" << (rate/1e6) << " MHz) exceeds\n"                  << "analog frontend filter bandwidth (" << (_codec_ctrl->get_bw_filter_range(dir).stop()/1e6) << " MHz)." -                << std::endl; +                ;              return false;          }          return true; @@ -218,7 +217,7 @@ class ad936x_manager_impl : public ad936x_manager          }          // Gains -        BOOST_FOREACH(const std::string &name, ad9361_ctrl::get_gain_names(key)) +        for(const std::string &name:  ad9361_ctrl::get_gain_names(key))          {              subtree->create<meta_range_t>(uhd::fs_path("gains") / name / "range")                  .set(ad9361_ctrl::get_gain_range(key)); @@ -278,7 +277,7 @@ class ad936x_manager_impl : public ad936x_manager          }          // Frontend filters -        BOOST_FOREACH(const std::string &filter_name, _codec_ctrl->get_filter_names(key)) { +        for(const std::string &filter_name:  _codec_ctrl->get_filter_names(key)) {              subtree->create<filter_info_base::sptr>(uhd::fs_path("filters") / filter_name / "value" )                  .set_publisher(boost::bind(&ad9361_ctrl::get_filter, _codec_ctrl, key, filter_name))                  .add_coerced_subscriber(boost::bind(&ad9361_ctrl::set_filter, _codec_ctrl, key, filter_name, _1)); diff --git a/host/lib/usrp/common/ad936x_manager.hpp b/host/lib/usrp/common/ad936x_manager.hpp index c456715e3..99464d0af 100644 --- a/host/lib/usrp/common/ad936x_manager.hpp +++ b/host/lib/usrp/common/ad936x_manager.hpp @@ -22,6 +22,7 @@  #include <uhd/utils/math.hpp>  #include <uhd/property_tree.hpp>  #include <uhd/types/direction.hpp> +#include <boost/format.hpp>  #include <boost/shared_ptr.hpp>  #include "ad9361_ctrl.hpp"  #include <stdint.h> diff --git a/host/lib/usrp/common/adf4001_ctrl.cpp b/host/lib/usrp/common/adf4001_ctrl.cpp index 01a35dbec..b824824a4 100644 --- a/host/lib/usrp/common/adf4001_ctrl.cpp +++ b/host/lib/usrp/common/adf4001_ctrl.cpp @@ -22,7 +22,7 @@  #include "adf4001_ctrl.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <iostream>  #include <iomanip> diff --git a/host/lib/usrp/common/adf435x.hpp b/host/lib/usrp/common/adf435x.hpp index ff7b1a2f4..18d5b70ba 100644 --- a/host/lib/usrp/common/adf435x.hpp +++ b/host/lib/usrp/common/adf435x.hpp @@ -268,14 +268,15 @@ public:                                          adf435x_regs_t::LDF_FRAC_N;          std::string tuning_str = (int_n_mode) ? "Integer-N" : "Fractional"; -        UHD_LOGV(often) -            << boost::format("ADF 435X Frequencies (MHz): REQUESTED=%0.9f, ACTUAL=%0.9f" -            ) % (target_freq/1e6) % (actual_freq/1e6) << std::endl -            << boost::format("ADF 435X Intermediates (MHz): Feedback=%0.2f, VCO=%0.2f, PFD=%0.2f, BAND=%0.2f, REF=%0.2f" -            ) % (feedback_freq/1e6) % (vco_freq/1e6) % (pfd_freq/1e6) % (pfd_freq/BS/1e6) % (_reference_freq/1e6) << std::endl -            << boost::format("ADF 435X Tuning: %s") % tuning_str.c_str() << std::endl -            << boost::format("ADF 435X Settings: R=%d, BS=%d, N=%d, FRAC=%d, MOD=%d, T=%d, D=%d, RFdiv=%d" -            ) % R % BS % N % FRAC % MOD % T % D % RFdiv << std::endl; +        UHD_LOGGER_TRACE("ADF435X") +            << boost::format("ADF 435X Frequencies (MHz): REQUESTED=%0.9f, ACTUAL=%0.9f") +                % (target_freq/1e6) % (actual_freq/1e6) +            << boost::format("ADF 435X Intermediates (MHz): Feedback=%0.2f, VCO=%0.2f, PFD=%0.2f, BAND=%0.2f, REF=%0.2f") +                % (feedback_freq/1e6) % (vco_freq/1e6) % (pfd_freq/1e6) % (pfd_freq/BS/1e6) % (_reference_freq/1e6) +            << boost::format("ADF 435X Tuning: %s") % tuning_str.c_str() +            << boost::format("ADF 435X Settings: R=%d, BS=%d, N=%d, FRAC=%d, MOD=%d, T=%d, D=%d, RFdiv=%d") +                % R % BS % N % FRAC % MOD % T % D % RFdiv +        ;          UHD_ASSERT_THROW((_regs.frac_12_bit          & ((uint16_t)~0xFFF)) == 0);          UHD_ASSERT_THROW((_regs.mod_12_bit           & ((uint16_t)~0xFFF)) == 0); diff --git a/host/lib/usrp/common/apply_corrections.cpp b/host/lib/usrp/common/apply_corrections.cpp index 272e0e093..32c7e3c45 100644 --- a/host/lib/usrp/common/apply_corrections.cpp +++ b/host/lib/usrp/common/apply_corrections.cpp @@ -18,11 +18,10 @@  #include "apply_corrections.hpp"  #include <uhd/usrp/dboard_eeprom.hpp>  #include <uhd/utils/paths.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/csv.hpp>  #include <uhd/types/dict.hpp>  #include <boost/filesystem.hpp> -#include <boost/foreach.hpp>  #include <boost/thread/mutex.hpp>  #include <cstdio>  #include <complex> @@ -114,7 +113,7 @@ static void apply_fe_corrections(          bool read_data = false, skip_next = false;;          std::vector<fe_cal_t> datas; -        BOOST_FOREACH(const uhd::csv::row_type &row, rows){ +        for(const uhd::csv::row_type &row:  rows){              if (not read_data and not row.empty() and row[0] == "DATA STARTS HERE"){                  read_data = true;                  skip_next = true; @@ -133,7 +132,7 @@ static void apply_fe_corrections(          }          std::sort(datas.begin(), datas.end(), fe_cal_comp);          fe_cal_cache[cal_data_path.string()] = datas; -        UHD_MSG(status) << "Loaded " << cal_data_path.string() << std::endl; +        UHD_LOGGER_INFO("CAL") << "Calibration data loaded: " << cal_data_path.string();      } @@ -168,7 +167,7 @@ void uhd::usrp::apply_tx_fe_corrections( //overloading to work according to rfno          );      }      catch(const std::exception &e){ -        UHD_MSG(error) << "Failure in apply_tx_fe_corrections: " << e.what() << std::endl; +        UHD_LOGGER_ERROR("CAL") << "Failure in apply_tx_fe_corrections: " << e.what();      }  } @@ -195,7 +194,7 @@ void uhd::usrp::apply_tx_fe_corrections(          );      }      catch(const std::exception &e){ -        UHD_MSG(error) << "Failure in apply_tx_fe_corrections: " << e.what() << std::endl; +        UHD_LOGGER_ERROR("CAL") << "Failure in apply_tx_fe_corrections: " << e.what();      }  } @@ -216,7 +215,7 @@ void uhd::usrp::apply_rx_fe_corrections( //overloading to work according to rfno          );      }      catch(const std::exception &e){ -        UHD_MSG(error) << "Failure in apply_tx_fe_corrections: " << e.what() << std::endl; +        UHD_LOGGER_ERROR("CAL") << "Failure in apply_tx_fe_corrections: " << e.what();      }  } @@ -236,6 +235,6 @@ void uhd::usrp::apply_rx_fe_corrections(          );      }      catch(const std::exception &e){ -        UHD_MSG(error) << "Failure in apply_rx_fe_corrections: " << e.what() << std::endl; +        UHD_LOGGER_ERROR("CAL") << "Failure in apply_rx_fe_corrections: " << e.what();      }  } diff --git a/host/lib/usrp/common/async_packet_handler.hpp b/host/lib/usrp/common/async_packet_handler.hpp index 20409c77a..fd4fed81e 100644 --- a/host/lib/usrp/common/async_packet_handler.hpp +++ b/host/lib/usrp/common/async_packet_handler.hpp @@ -22,7 +22,7 @@  #include <uhd/transport/vrt_if_packet.hpp>  #include <uhd/types/metadata.hpp>  #include <uhd/utils/byteswap.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  namespace uhd{ namespace usrp{ @@ -55,14 +55,23 @@ namespace uhd{ namespace usrp{          if (metadata.event_code &              ( async_metadata_t::EVENT_CODE_UNDERFLOW              | async_metadata_t::EVENT_CODE_UNDERFLOW_IN_PACKET) -        ) UHD_MSG(fastpath) << "U"; +            ) +        { +            UHD_LOG_FASTPATH("U") +        }          else if (metadata.event_code &              ( async_metadata_t::EVENT_CODE_SEQ_ERROR              | async_metadata_t::EVENT_CODE_SEQ_ERROR_IN_BURST) -        ) UHD_MSG(fastpath) << "S"; +            ) +        { +            UHD_LOG_FASTPATH("S") +        }          else if (metadata.event_code &              async_metadata_t::EVENT_CODE_TIME_ERROR -        ) UHD_MSG(fastpath) << "L"; +            ) +        { +            UHD_LOG_FASTPATH("L") +        }      } diff --git a/host/lib/usrp/common/constrained_device_args.hpp b/host/lib/usrp/common/constrained_device_args.hpp index 1bfd1df00..47c5f4cc0 100644 --- a/host/lib/usrp/common/constrained_device_args.hpp +++ b/host/lib/usrp/common/constrained_device_args.hpp @@ -260,7 +260,7 @@ namespace usrp {          template<typename arg_t, typename data_t>          static inline void _enforce_discrete(const arg_t& arg, const std::vector<data_t>& valid_values) {              bool match = false; -            BOOST_FOREACH(const data_t& val, valid_values) { +            for(const data_t& val:  valid_values) {                  if (val == arg.get()) {                      match = true;                      break; diff --git a/host/lib/usrp/common/fifo_ctrl_excelsior.cpp b/host/lib/usrp/common/fifo_ctrl_excelsior.cpp index a9995a161..c86380354 100644 --- a/host/lib/usrp/common/fifo_ctrl_excelsior.cpp +++ b/host/lib/usrp/common/fifo_ctrl_excelsior.cpp @@ -18,7 +18,7 @@  #include "fifo_ctrl_excelsior.hpp"  #include "async_packet_handler.hpp"  #include <uhd/exception.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/byteswap.hpp>  #include <uhd/utils/tasks.hpp>  #include <uhd/utils/safe_call.hpp> @@ -97,7 +97,7 @@ public:              vrt::if_hdr_unpack_le(pkt, packet_info);          }          catch(const std::exception &ex){ -            UHD_MSG(error) << "FIFO ctrl bad VITA packet: " << ex.what() << std::endl; +            UHD_LOGGER_ERROR("UHD") << "FIFO ctrl bad VITA packet: " << ex.what();          }          if (packet_info.has_sid and packet_info.sid == _config.ctrl_sid_base){              ctrl_result_t res = ctrl_result_t(); @@ -112,7 +112,7 @@ public:              standard_async_msg_prints(metadata);          }          else{ -            UHD_MSG(error) << "FIFO ctrl got unknown SID: " << packet_info.sid << std::endl; +            UHD_LOGGER_ERROR("UHD") << "FIFO ctrl got unknown SID: " << packet_info.sid ;          }      } diff --git a/host/lib/usrp/common/fx2_ctrl.cpp b/host/lib/usrp/common/fx2_ctrl.cpp index c69223747..9fa774851 100644 --- a/host/lib/usrp/common/fx2_ctrl.cpp +++ b/host/lib/usrp/common/fx2_ctrl.cpp @@ -16,7 +16,7 @@  //  #include "fx2_ctrl.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/exception.hpp>  #include <uhd/transport/usb_control.hpp>  #include <boost/functional/hash.hpp> @@ -177,7 +177,7 @@ public:          unsigned char reset_n = 0;          //hit the reset line -        if (load_img_msg) UHD_MSG(status) << "Loading firmware image: " << filestring << "..." << std::flush; +        if (load_img_msg) UHD_LOGGER_INFO("FX2") << "Loading firmware image: " << filestring << "...";          usrp_control_write(FX2_FIRMWARE_LOAD, 0xe600, 0, &reset_y, 1);          while (!file.eof()) { @@ -205,7 +205,7 @@ public:                  //wait for things to settle                  boost::this_thread::sleep(boost::posix_time::milliseconds(1000)); -                if (load_img_msg) UHD_MSG(status) << " done" << std::endl; +                if (load_img_msg) UHD_LOGGER_INFO("FX2") << "Firmware loaded";                  return;              }              //type anything else is unhandled @@ -242,7 +242,7 @@ public:          const int ep0_size = 64;          unsigned char buf[ep0_size]; -        if (load_img_msg) UHD_MSG(status) << "Loading FPGA image: " << filestring << "..." << std::flush; +        if (load_img_msg) UHD_LOGGER_INFO("FX2") << "Loading FPGA image: " << filestring << "...";          std::ifstream file;          file.open(filename, std::ios::in | std::ios::binary);          if (not file.good()) { @@ -274,12 +274,12 @@ public:          usrp_fpga_reset(false); //done loading, take fpga out of reset          file.close(); -        if (load_img_msg) UHD_MSG(status) << " done" << std::endl; +        if (load_img_msg) UHD_LOGGER_INFO("FX2") << "FPGA image loaded";      }      void usrp_load_eeprom(std::string filestring)      { -        if (load_img_msg) UHD_MSG(status) << "Loading EEPROM image: " << filestring << "..." << std::flush; +        if (load_img_msg) UHD_LOGGER_INFO("FX2") << "Loading EEPROM image: " << filestring << "...";          const char *filename = filestring.c_str();          const uint16_t i2c_addr = 0x50; @@ -315,7 +315,7 @@ public:              boost::this_thread::sleep(boost::posix_time::milliseconds(100));          }          file.close(); -        if (load_img_msg) UHD_MSG(status) << " done" << std::endl; +        if (load_img_msg) UHD_LOGGER_INFO("FX2") << "EEPROM image loaded";      } diff --git a/host/lib/usrp/common/max287x.hpp b/host/lib/usrp/common/max287x.hpp index 839ed77bc..c3c4bf18c 100644 --- a/host/lib/usrp/common/max287x.hpp +++ b/host/lib/usrp/common/max287x.hpp @@ -403,7 +403,7 @@ public:              while (vco_freq < MIN_VCO_FREQ)                  vco_freq *=2;              uint8_t vco_index = 0xFF; -            BOOST_FOREACH(const vco_map_t::value_type &vco, max2871_vco_map) +            for(const vco_map_t::value_type &vco:  max2871_vco_map)              {                  if (uhd::math::fp_compare::fp_compare_epsilon<double>(vco_freq) < vco.second.stop())                  { @@ -638,13 +638,14 @@ double max287x<max287x_regs_t>::set_frequency(      //actual frequency calculation      double actual_freq = double((N + (double(FRAC)/double(MOD)))*ref_freq*(1+int(D))/(R*(1+int(T)))) * fb_divisor / RFdiv; -    UHD_LOGV(rarely) -        << boost::format("MAX287x: Intermediates: ref=%0.2f, outdiv=%f, fbdiv=%f" -            ) % ref_freq % double(RFdiv*2) % double(N + double(FRAC)/double(MOD)) << std::endl -        << boost::format("MAX287x: tune: R=%d, BS=%d, N=%d, FRAC=%d, MOD=%d, T=%d, D=%d, RFdiv=%d, type=%s" -            ) % R % BS % N % FRAC % MOD % T % D % RFdiv % ((is_int_n) ? "Integer-N" : "Fractional") << std::endl -        << boost::format("MAX287x: Frequencies (MHz): REQ=%0.2f, ACT=%0.2f, VCO=%0.2f, PFD=%0.2f, BAND=%0.2f" -            ) % (target_freq/1e6) % (actual_freq/1e6) % (vco_freq/1e6) % (pfd_freq/1e6) % (pfd_freq/BS/1e6) << std::endl; +    UHD_LOGGER_TRACE("MAX287X") +        << boost::format("MAX287x: Intermediates: ref=%0.2f, outdiv=%f, fbdiv=%f") +            % ref_freq % double(RFdiv*2) % double(N + double(FRAC)/double(MOD)) +        << boost::format("MAX287x: tune: R=%d, BS=%d, N=%d, FRAC=%d, MOD=%d, T=%d, D=%d, RFdiv=%d, type=%s") +            % R % BS % N % FRAC % MOD % T % D % RFdiv % ((is_int_n) ? "Integer-N" : "Fractional") +        << boost::format("MAX287x: Frequencies (MHz): REQ=%0.2f, ACT=%0.2f, VCO=%0.2f, PFD=%0.2f, BAND=%0.2f") +            % (target_freq/1e6) % (actual_freq/1e6) % (vco_freq/1e6) % (pfd_freq/1e6) % (pfd_freq/BS/1e6) +    ;      //load the register values      _regs.rf_output_enable = max287x_regs_t::RF_OUTPUT_ENABLE_ENABLED; diff --git a/host/lib/usrp/common/recv_packet_demuxer.cpp b/host/lib/usrp/common/recv_packet_demuxer.cpp index 8d9dcee9e..2a4c4d705 100644 --- a/host/lib/usrp/common/recv_packet_demuxer.cpp +++ b/host/lib/usrp/common/recv_packet_demuxer.cpp @@ -16,7 +16,7 @@  //  #include "recv_packet_demuxer.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/byteswap.hpp>  #include <boost/thread/mutex.hpp>  #include <uhd/transport/vrt_if_packet.hpp> @@ -87,7 +87,7 @@ public:              if (rx_index < _queues.size()) _queues[rx_index].wrapper.push(buff);              else              { -                UHD_MSG(error) << "Got a data packet with unknown SID " << extract_sid(buff) << std::endl; +                UHD_LOGGER_ERROR("STREAMER") << "Got a data packet with unknown SID " << extract_sid(buff) ;                  recv_pkt_demux_mrb *mrb = new recv_pkt_demux_mrb();                  vrt::if_packet_info_t info;                  info.packet_type = vrt::if_packet_info_t::PACKET_TYPE_DATA; diff --git a/host/lib/usrp/common/recv_packet_demuxer_3000.hpp b/host/lib/usrp/common/recv_packet_demuxer_3000.hpp index 3ad76f1a0..5305c8ddd 100644 --- a/host/lib/usrp/common/recv_packet_demuxer_3000.hpp +++ b/host/lib/usrp/common/recv_packet_demuxer_3000.hpp @@ -1,5 +1,5 @@  // -// Copyright 2013 Ettus Research LLC +// Copyright 2013,2017 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 @@ -20,15 +20,14 @@  #include <uhd/config.hpp>  #include <uhd/transport/zero_copy.hpp> -#include <stdint.h> -#include <boost/thread.hpp> -#include <uhd/utils/msg.hpp> -#include <uhd/utils/atomic.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/types/time_spec.hpp>  #include <uhd/utils/byteswap.hpp> +#include <boost/thread.hpp> +#include <boost/enable_shared_from_this.hpp>  #include <queue>  #include <map> -#include <boost/enable_shared_from_this.hpp> +#include <stdint.h>  namespace uhd{ namespace usrp{ @@ -77,24 +76,6 @@ namespace uhd{ namespace usrp{                      return buff;                  }              } -            // Following is disabled by default as super_recv_packet_handler (caller) is not thread safe -            // Only underlying transport (libusb1_zero_copy) is thread safe -            // The onus is on the caller to super_recv_packet_handler (and therefore this) to serialise access -#ifdef RECV_PACKET_DEMUXER_3000_THREAD_SAFE -            //---------------------------------------------------------- -            //-- Try to claim the transport or wait patiently -            //---------------------------------------------------------- -            if (_claimed.cas(1, 0)) -            { -                boost::mutex::scoped_lock l(mutex); -                cond.timed_wait(l, boost::posix_time::microseconds(long(timeout*1e6))); -            } - -            //---------------------------------------------------------- -            //-- Wait on the transport for input buffers -            //---------------------------------------------------------- -            else -#endif // RECV_PACKET_DEMUXER_3000_THREAD_SAFE              {                  buff = _xport->get_recv_buff(timeout);                  if (buff) @@ -103,17 +84,13 @@ namespace uhd{ namespace usrp{                      if (new_sid != sid)                      {                          boost::mutex::scoped_lock l(mutex); -                        if (_queues.count(new_sid) == 0) UHD_MSG(error) +                        if (_queues.count(new_sid) == 0) UHD_LOGGER_ERROR("STREAMER")                              << "recv packet demuxer unexpected sid 0x" << std::hex << new_sid << std::dec -                            << std::endl; +                            ;                          else _queues[new_sid].push(buff);                          buff.reset();                      }                  } -#ifdef RECV_PACKET_DEMUXER_3000_THREAD_SAFE -                _claimed.write(0); -                cond.notify_all(); -#endif // RECV_PACKET_DEMUXER_3000_THREAD_SAFE              }              return buff;          } @@ -132,10 +109,6 @@ namespace uhd{ namespace usrp{          typedef std::queue<transport::managed_recv_buffer::sptr> queue_type_t;          std::map<uint32_t, queue_type_t> _queues;          transport::zero_copy_if::sptr _xport; -#ifdef RECV_PACKET_DEMUXER_3000_THREAD_SAFE -        uhd::atomic_uint32_t _claimed; -        boost::condition_variable cond; -#endif // RECV_PACKET_DEMUXER_3000_THREAD_SAFE          boost::mutex mutex;      }; diff --git a/host/lib/usrp/common/validate_subdev_spec.cpp b/host/lib/usrp/common/validate_subdev_spec.cpp index fab40b204..76e61221e 100644 --- a/host/lib/usrp/common/validate_subdev_spec.cpp +++ b/host/lib/usrp/common/validate_subdev_spec.cpp @@ -18,7 +18,6 @@  #include "validate_subdev_spec.hpp"  #include <uhd/exception.hpp>  #include <uhd/utils/assert_has.hpp> -#include <boost/foreach.hpp>  #include <boost/format.hpp>  using namespace uhd; @@ -52,19 +51,19 @@ void uhd::usrp::validate_subdev_spec(      //make a list of all possible specs      subdev_spec_t all_specs; -    BOOST_FOREACH(const std::string &db, tree->list(str(boost::format("/mboards/%s/dboards") % mb))){ -        BOOST_FOREACH(const std::string &sd, tree->list(str(boost::format("/mboards/%s/dboards/%s/%s_frontends") % mb % db % type))){ +    for(const std::string &db:  tree->list(str(boost::format("/mboards/%s/dboards") % mb))){ +        for(const std::string &sd:  tree->list(str(boost::format("/mboards/%s/dboards/%s/%s_frontends") % mb % db % type))){              all_specs.push_back(subdev_spec_pair_t(db, sd));          }      }      //validate that the spec is possible -    BOOST_FOREACH(const subdev_spec_pair_t &pair, spec){ +    for(const subdev_spec_pair_t &pair:  spec){          uhd::assert_has(all_specs, pair, str(boost::format("%s subdevice specification on mboard %s") % type % mb));      }      //enable selected frontends, disable others -    BOOST_FOREACH(const subdev_spec_pair_t &pair, all_specs){ +    for(const subdev_spec_pair_t &pair:  all_specs){          const bool enb = uhd::has(spec, pair);          tree->access<bool>(str(boost::format(              "/mboards/%s/dboards/%s/%s_frontends/%s/enabled" diff --git a/host/lib/usrp/cores/dma_fifo_core_3000.cpp b/host/lib/usrp/cores/dma_fifo_core_3000.cpp index e1a841b96..18c79f4c5 100644 --- a/host/lib/usrp/cores/dma_fifo_core_3000.cpp +++ b/host/lib/usrp/cores/dma_fifo_core_3000.cpp @@ -19,7 +19,7 @@  #include <uhd/exception.hpp>  #include <boost/thread/thread.hpp> //sleep  #include <uhd/utils/soft_register.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  using namespace uhd; diff --git a/host/lib/usrp/cores/i2c_core_100.cpp b/host/lib/usrp/cores/i2c_core_100.cpp index 029b6eaa7..e68dc2ea6 100644 --- a/host/lib/usrp/cores/i2c_core_100.cpp +++ b/host/lib/usrp/cores/i2c_core_100.cpp @@ -17,7 +17,7 @@  #include "i2c_core_100.hpp"  #include <uhd/exception.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <boost/thread/thread.hpp> //sleep  #define REG_I2C_PRESCALER_LO _base + 0 @@ -127,7 +127,7 @@ private:              if ((_iface->peek16(REG_I2C_CMD_STATUS) & I2C_ST_TIP) == 0) return;              boost::this_thread::sleep(boost::posix_time::milliseconds(1));          } -        UHD_MSG(error) << "i2c_core_100: i2c_wait timeout" << std::endl; +        UHD_LOGGER_ERROR("CORES") << "i2c_core_100: i2c_wait timeout" ;      }      bool wait_chk_ack(void){ diff --git a/host/lib/usrp/cores/i2c_core_100_wb32.cpp b/host/lib/usrp/cores/i2c_core_100_wb32.cpp index 099b80447..8e03a8c3c 100644 --- a/host/lib/usrp/cores/i2c_core_100_wb32.cpp +++ b/host/lib/usrp/cores/i2c_core_100_wb32.cpp @@ -17,7 +17,7 @@  #include "i2c_core_100_wb32.hpp"  #include <uhd/exception.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <boost/thread/thread.hpp> //sleep  #define REG_I2C_PRESCALER_LO _base + 0 @@ -138,7 +138,7 @@ private:              if ((_iface->peek32(REG_I2C_CMD_STATUS) & I2C_ST_TIP) == 0) return;              boost::this_thread::sleep(boost::posix_time::milliseconds(1));          } -        UHD_MSG(error) << "i2c_core_100_wb32: i2c_wait timeout" << std::endl; +        UHD_LOGGER_ERROR("CORES") << "i2c_core_100_wb32: i2c_wait timeout" ;      }      bool wait_chk_ack(void){ diff --git a/host/lib/usrp/cores/i2c_core_200.cpp b/host/lib/usrp/cores/i2c_core_200.cpp index eae91253c..7b28573e9 100644 --- a/host/lib/usrp/cores/i2c_core_200.cpp +++ b/host/lib/usrp/cores/i2c_core_200.cpp @@ -17,7 +17,7 @@  #include "i2c_core_200.hpp"  #include <uhd/exception.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <boost/thread/thread.hpp> //sleep  #include <boost/thread/mutex.hpp> @@ -130,7 +130,7 @@ private:              if ((this->peek(REG_I2C_RD_ST) & I2C_ST_TIP) == 0) return;              boost::this_thread::sleep(boost::posix_time::milliseconds(1));          } -        UHD_MSG(error) << "i2c_core_200: i2c_wait timeout" << std::endl; +        UHD_LOGGER_ERROR("CORES") << "i2c_core_200: i2c_wait timeout" ;      }      bool wait_chk_ack(void){ diff --git a/host/lib/usrp/cores/radio_ctrl_core_3000.cpp b/host/lib/usrp/cores/radio_ctrl_core_3000.cpp index 2e405d735..512a860e0 100644 --- a/host/lib/usrp/cores/radio_ctrl_core_3000.cpp +++ b/host/lib/usrp/cores/radio_ctrl_core_3000.cpp @@ -18,7 +18,7 @@  #include "radio_ctrl_core_3000.hpp"  #include "async_packet_handler.hpp"  #include <uhd/exception.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/byteswap.hpp>  #include <uhd/utils/safe_call.hpp>  #include <uhd/transport/bounded_buffer.hpp> @@ -165,7 +165,7 @@ private:          //load payload          pkt[packet_info.num_header_words32+0] = (_bige)? uhd::htonx(addr) : uhd::htowx(addr);          pkt[packet_info.num_header_words32+1] = (_bige)? uhd::htonx(data) : uhd::htowx(data); -        //UHD_MSG(status) << boost::format("0x%08x, 0x%08x\n") % addr % data; +        //UHD_LOGGER_INFO("radio_ctrl") << boost::format("0x%08x, 0x%08x\n") % addr % data;          //send the buffer over the interface          _outstanding_seqs.push(_seq_out);          buff->commit(sizeof(uint32_t)*(packet_info.num_packet_words32)); @@ -243,17 +243,17 @@ private:              }              catch(const std::exception &ex)              { -                UHD_MSG(error) << "Radio ctrl bad VITA packet: " << ex.what() << std::endl; +                UHD_LOGGER_ERROR("radio_ctrl") << "Radio ctrl bad VITA packet: " << ex.what() ;                  if (buff){                      UHD_VAR(buff->size());                  }                  else{ -                    UHD_MSG(status) << "buff is NULL" << std::endl; +                    UHD_LOGGER_INFO("radio_ctrl") << "buff is NULL" ;                  } -                UHD_MSG(status) << std::hex << pkt[0] << std::dec << std::endl; -                UHD_MSG(status) << std::hex << pkt[1] << std::dec << std::endl; -                UHD_MSG(status) << std::hex << pkt[2] << std::dec << std::endl; -                UHD_MSG(status) << std::hex << pkt[3] << std::dec << std::endl; +                UHD_LOGGER_INFO("radio_ctrl") << std::hex << pkt[0] << std::dec ; +                UHD_LOGGER_INFO("radio_ctrl") << std::hex << pkt[1] << std::dec ; +                UHD_LOGGER_INFO("radio_ctrl") << std::hex << pkt[2] << std::dec ; +                UHD_LOGGER_INFO("radio_ctrl") << std::hex << pkt[3] << std::dec ;              }              //check the buffer diff --git a/host/lib/usrp/cores/rx_dsp_core_200.cpp b/host/lib/usrp/cores/rx_dsp_core_200.cpp index e781cfc6d..465a3b913 100644 --- a/host/lib/usrp/cores/rx_dsp_core_200.cpp +++ b/host/lib/usrp/cores/rx_dsp_core_200.cpp @@ -20,7 +20,7 @@  #include <uhd/types/dict.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/math.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp>  #include <boost/assign/list_of.hpp>  #include <boost/thread/thread.hpp> //thread sleep @@ -195,7 +195,7 @@ public:          if (decim > 1 and hb0 == 0 and hb1 == 0)          { -            UHD_MSG(warning) << boost::format( +            UHD_LOGGER_WARNING("CORES") << boost::format(                  "The requested decimation is odd; the user should expect CIC rolloff.\n"                  "Select an even decimation to ensure that a halfband filter is enabled.\n"                  "decimation = dsp_rate/samp_rate -> %d = (%f MHz)/(%f MHz)\n" diff --git a/host/lib/usrp/cores/rx_dsp_core_3000.cpp b/host/lib/usrp/cores/rx_dsp_core_3000.cpp index fdd73a7ac..45e4c6f49 100644 --- a/host/lib/usrp/cores/rx_dsp_core_3000.cpp +++ b/host/lib/usrp/cores/rx_dsp_core_3000.cpp @@ -20,7 +20,7 @@  #include <uhd/types/dict.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/math.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp>  #include <boost/assign/list_of.hpp>  #include <boost/thread/thread.hpp> //thread sleep @@ -169,7 +169,7 @@ public:              _iface->poke32(REG_DSP_RX_DECIM, (hb0 << 9) /*small HB */ | (hb1 << 8) /*large HB*/ | (decim & 0xff));              if (decim > 1 and hb0 == 0 and hb1 == 0) { -                UHD_MSG(warning) << boost::format( +                UHD_LOGGER_WARNING("CORES") << boost::format(                      "The requested decimation is odd; the user should expect CIC rolloff.\n"                      "Select an even decimation to ensure that a halfband filter is enabled.\n"                      "decimation = dsp_rate/samp_rate -> %d = (%f MHz)/(%f MHz)\n" @@ -189,7 +189,7 @@ public:              _iface->poke32(REG_DSP_RX_DECIM,  (hb_enable << 8) | (decim & 0xff));              if (decim > 1 and hb0 == 0 and hb1 == 0 and hb2 == 0) { -                UHD_MSG(warning) << boost::format( +                UHD_LOGGER_WARNING("CORES") << boost::format(                      "The requested decimation is odd; the user should expect passband CIC rolloff.\n"                      "Select an even decimation to ensure that a halfband filter is enabled.\n"                      "Decimations factorable by 4 will enable 2 halfbands, those factorable by 8 will enable 3 halfbands.\n" diff --git a/host/lib/usrp/cores/rx_vita_core_3000.cpp b/host/lib/usrp/cores/rx_vita_core_3000.cpp index 57868ff54..e10913a22 100644 --- a/host/lib/usrp/cores/rx_vita_core_3000.cpp +++ b/host/lib/usrp/cores/rx_vita_core_3000.cpp @@ -16,7 +16,7 @@  //  #include "rx_vita_core_3000.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp>  #include <boost/assign/list_of.hpp>  #include <boost/tuple/tuple.hpp> @@ -96,7 +96,7 @@ struct rx_vita_core_3000_impl : rx_vita_core_3000      {          if (not _is_setup)          { -            //UHD_MSG(warning) << "rx vita core 3000 issue stream command - not setup yet!"; +            //UHD_LOGGER_WARNING("CORES") << "rx vita core 3000 issue stream command - not setup yet!";              return;          }          UHD_ASSERT_THROW(stream_cmd.num_samps <= 0x0fffffff); diff --git a/host/lib/usrp/cores/spi_core_100.cpp b/host/lib/usrp/cores/spi_core_100.cpp index 22b163b14..4d61821b4 100644 --- a/host/lib/usrp/cores/spi_core_100.cpp +++ b/host/lib/usrp/cores/spi_core_100.cpp @@ -17,7 +17,7 @@  #include "spi_core_100.hpp"  #include <uhd/exception.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <boost/thread/thread.hpp> //sleep  #define REG_SPI_TXRX0 _base + 0 @@ -80,7 +80,7 @@ private:              if ((_iface->peek16(REG_SPI_CTRL) & SPI_CTRL_GO_BSY) == 0) return;              boost::this_thread::sleep(boost::posix_time::milliseconds(1));          } -        UHD_MSG(error) << "spi_core_100: spi_wait timeout" << std::endl; +        UHD_LOGGER_ERROR("CORES") << "spi_core_100: spi_wait timeout" ;      }      wb_iface::sptr _iface; diff --git a/host/lib/usrp/cores/spi_core_3000.cpp b/host/lib/usrp/cores/spi_core_3000.cpp index 78b0af1a3..2abbac317 100644 --- a/host/lib/usrp/cores/spi_core_3000.cpp +++ b/host/lib/usrp/cores/spi_core_3000.cpp @@ -17,7 +17,7 @@  #include "spi_core_3000.hpp"  #include <uhd/exception.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <boost/thread/thread.hpp> //sleep  #define SPI_DIV      _base + 0 diff --git a/host/lib/usrp/cores/time_core_3000.cpp b/host/lib/usrp/cores/time_core_3000.cpp index 25142b9fe..296923756 100644 --- a/host/lib/usrp/cores/time_core_3000.cpp +++ b/host/lib/usrp/cores/time_core_3000.cpp @@ -17,7 +17,7 @@  #include "time_core_3000.hpp"  #include <uhd/utils/safe_call.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <boost/thread/thread.hpp>  #define REG_TIME_HI       _base + 0 @@ -63,21 +63,21 @@ struct time_core_3000_impl : time_core_3000      void self_test(void)      {          const size_t sleep_millis = 100; -        UHD_MSG(status) << "Performing timer loopback test... " << std::flush; +        UHD_LOGGER_INFO("CORES") << "Performing timer loopback test... ";          const time_spec_t time0 = this->get_time_now();          boost::this_thread::sleep(boost::posix_time::milliseconds(sleep_millis));          const time_spec_t time1 = this->get_time_now();          const double approx_secs = (time1 - time0).get_real_secs();          const bool test_fail = (approx_secs > 0.15) or (approx_secs < 0.05); -        UHD_MSG(status) << ((test_fail)? " fail" : "pass") << std::endl; +        UHD_LOGGER_INFO("CORES") << "Timer loopback test " << ((test_fail)? "failed" : "passed");          //useful warning for debugging actual rate          const size_t ticks_elapsed = size_t(_tick_rate*approx_secs);          const size_t approx_rate = size_t(ticks_elapsed/(sleep_millis/1e3)); -        if (test_fail) UHD_MSG(warning) +        if (test_fail) UHD_LOGGER_WARNING("CORES")              << "Expecting clock rate: " << (_tick_rate/1e6) << " MHz\n"              << "Approximate clock rate: " << (approx_rate/1e6) << " MHz\n" -        << std::endl; +        ;      }      uhd::time_spec_t get_time_now(void) diff --git a/host/lib/usrp/cores/tx_dsp_core_200.cpp b/host/lib/usrp/cores/tx_dsp_core_200.cpp index 4e1743ee1..f1bf560dc 100644 --- a/host/lib/usrp/cores/tx_dsp_core_200.cpp +++ b/host/lib/usrp/cores/tx_dsp_core_200.cpp @@ -20,7 +20,7 @@  #include <uhd/types/dict.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/math.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <boost/assign/list_of.hpp>  #include <boost/math/special_functions/round.hpp>  #include <boost/thread/thread.hpp> //sleep @@ -135,7 +135,7 @@ public:          if (interp > 1 and hb0 == 0 and hb1 == 0)          { -            UHD_MSG(warning) << boost::format( +            UHD_LOGGER_WARNING("CORES") << boost::format(                  "The requested interpolation is odd; the user should expect CIC rolloff.\n"                  "Select an even interpolation to ensure that a halfband filter is enabled.\n"                  "interpolation = dsp_rate/samp_rate -> %d = (%f MHz)/(%f MHz)\n" diff --git a/host/lib/usrp/cores/tx_dsp_core_3000.cpp b/host/lib/usrp/cores/tx_dsp_core_3000.cpp index 67ff418b3..c30e8dfc1 100644 --- a/host/lib/usrp/cores/tx_dsp_core_3000.cpp +++ b/host/lib/usrp/cores/tx_dsp_core_3000.cpp @@ -20,7 +20,7 @@  #include <uhd/types/dict.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/math.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <boost/assign/list_of.hpp>  #include <boost/math/special_functions/round.hpp>  #include <boost/thread/thread.hpp> //sleep @@ -103,7 +103,7 @@ public:          if (interp > 1 and hb0 == 0 and hb1 == 0)          { -            UHD_MSG(warning) << boost::format( +            UHD_LOGGER_WARNING("CORES") << boost::format(                  "The requested interpolation is odd; the user should expect CIC rolloff.\n"                  "Select an even interpolation to ensure that a halfband filter is enabled.\n"                  "interpolation = dsp_rate/samp_rate -> %d = (%f MHz)/(%f MHz)\n" diff --git a/host/lib/usrp/dboard/db_basic_and_lf.cpp b/host/lib/usrp/dboard/db_basic_and_lf.cpp index 941a80ea4..a3d9fb316 100644 --- a/host/lib/usrp/dboard/db_basic_and_lf.cpp +++ b/host/lib/usrp/dboard/db_basic_and_lf.cpp @@ -19,7 +19,7 @@  #include <uhd/types/ranges.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/static.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/usrp/dboard_base.hpp>  #include <uhd/usrp/dboard_manager.hpp>  #include <boost/assign/list_of.hpp> diff --git a/host/lib/usrp/dboard/db_cbx.cpp b/host/lib/usrp/dboard/db_cbx.cpp index c27cbf58a..cc98205e9 100644 --- a/host/lib/usrp/dboard/db_cbx.cpp +++ b/host/lib/usrp/dboard/db_cbx.cpp @@ -40,7 +40,7 @@ sbx_xcvr::cbx::~cbx(void){  void sbx_xcvr::cbx::write_lo_regs(dboard_iface::unit_t unit, const std::vector<uint32_t> ®s)  { -    BOOST_FOREACH(uint32_t reg, regs) +    for(uint32_t reg:  regs)      {          self_base->get_iface()->write_spi(unit, spi_config_t::EDGE_RISE, reg, 32);      } @@ -51,9 +51,9 @@ void sbx_xcvr::cbx::write_lo_regs(dboard_iface::unit_t unit, const std::vector<u   * Tuning   **********************************************************************/  double sbx_xcvr::cbx::set_lo_freq(dboard_iface::unit_t unit, double target_freq) { -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("CBX") << boost::format(          "CBX tune: target frequency %f MHz" -    ) % (target_freq/1e6) << std::endl; +    ) % (target_freq/1e6) ;      //clip the input      target_freq = cbx_freq_range.clip(target_freq); diff --git a/host/lib/usrp/dboard/db_dbsrx.cpp b/host/lib/usrp/dboard/db_dbsrx.cpp index f296820c5..ecfeb5308 100644 --- a/host/lib/usrp/dboard/db_dbsrx.cpp +++ b/host/lib/usrp/dboard/db_dbsrx.cpp @@ -24,7 +24,7 @@  #include <uhd/utils/static.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/algorithm.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/types/ranges.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/types/dict.hpp> @@ -98,9 +98,9 @@ private:              //get the register data              for(int i=0; i<num_bytes; i++){                  regs_vector[1+i] = _max2118_write_regs.get_reg(start_addr+i); -                UHD_LOGV(often) << boost::format( +                UHD_LOGGER_TRACE("DBSRX") << boost::format(                      "DBSRX: send reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" -                ) % int(start_addr+i) % int(regs_vector[1+i]) % int(start_addr) % num_bytes << std::endl; +                ) % int(start_addr+i) % int(regs_vector[1+i]) % int(start_addr) % num_bytes ;              }              //send the data @@ -130,9 +130,9 @@ private:                  if (i + start_addr >= status_addr){                      _max2118_read_regs.set_reg(i + start_addr, regs_vector[i]);                  } -                UHD_LOGV(often) << boost::format( +                UHD_LOGGER_TRACE("DBSRX") << boost::format(                      "DBSRX: read reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" -                ) % int(start_addr+i) % int(regs_vector[i]) % int(start_addr) % num_bytes << std::endl; +                ) % int(start_addr+i) % int(regs_vector[i]) % int(start_addr) % num_bytes ;              }          }      } @@ -147,9 +147,9 @@ private:          //mask and return lock detect          bool locked = 5 >= _max2118_read_regs.adc and _max2118_read_regs.adc >= 2; -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("DBSRX") << boost::format(              "DBSRX: locked %d" -        ) % locked << std::endl; +        ) % locked ;          return sensor_value_t("LO", locked, "locked", "unlocked");      } @@ -175,7 +175,7 @@ UHD_STATIC_BLOCK(reg_dbsrx_dboard){  dbsrx::dbsrx(ctor_args_t args) : rx_dboard_base(args){      //warn user about incorrect DBID on USRP1, requires R193 populated      if (this->get_iface()->get_special_props().soft_clock_divider and this->get_rx_id() == 0x000D) -        UHD_MSG(warning) << boost::format( +        UHD_LOGGER_WARNING("DBSRX") << boost::format(                  "DBSRX: incorrect dbid\n"                  "Expected dbid 0x0002 and R193\n"                  "found dbid == %d\n" @@ -184,7 +184,7 @@ dbsrx::dbsrx(ctor_args_t args) : rx_dboard_base(args){      //warn user about incorrect DBID on non-USRP1, requires R194 populated      if (not this->get_iface()->get_special_props().soft_clock_divider and this->get_rx_id() == 0x0002) -        UHD_MSG(warning) << boost::format( +        UHD_LOGGER_WARNING("DBSRX") << boost::format(                  "DBSRX: incorrect dbid\n"                  "Expected dbid 0x000D and R194\n"                  "found dbid == %d\n" @@ -205,7 +205,7 @@ dbsrx::dbsrx(ctor_args_t args) : rx_dboard_base(args){          .set("DBSRX");      this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked")          .set_publisher(boost::bind(&dbsrx::get_locked, this)); -    BOOST_FOREACH(const std::string &name, dbsrx_gain_ranges.keys()){ +    for(const std::string &name:  dbsrx_gain_ranges.keys()){          this->get_rx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&dbsrx::set_gain, this, _1, name))              .set(dbsrx_gain_ranges[name].start()); @@ -266,7 +266,7 @@ double dbsrx::set_lo_freq(double target_freq){      //choose refclock      std::vector<double> clock_rates = this->get_iface()->get_clock_rates(dboard_iface::UNIT_RX);      const double max_clock_rate = uhd::sorted(clock_rates).back(); -    BOOST_FOREACH(ref_clock, uhd::reversed(uhd::sorted(clock_rates))){ +    for(auto ref_clock:  uhd::reversed(uhd::sorted(clock_rates))){          //USRP1 feeds the DBSRX clock from a FPGA GPIO line.          //make sure that this clock does not exceed rate limit.          if (this->get_iface()->get_special_props().soft_clock_divider){ @@ -279,17 +279,17 @@ double dbsrx::set_lo_freq(double target_freq){          m = 31;          while ((ref_clock/m < 1e6 or ref_clock/m > 2.5e6) and m > 0){ m--; } -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("DBSRX") << boost::format(              "DBSRX: trying ref_clock %f and m_divider %d" -        ) % (ref_clock) % m << std::endl; +        ) % (ref_clock) % m ;          if (m >= 32) continue;          //choose R -        for(r = 0; r <= 6; r += 1) { +        for(auto r = 0; r <= 6; r += 1) {              //compute divider from setting              R = 1 << (r+1); -            UHD_LOGV(often) << boost::format("DBSRX R:%d\n") % R << std::endl; +            UHD_LOGGER_TRACE("DBSRX") << boost::format("DBSRX R:%d\n") % R ;              //compute PFD compare frequency = ref_clock/R              pfd_freq = ref_clock / R; @@ -315,9 +315,9 @@ double dbsrx::set_lo_freq(double target_freq){      UHD_ASSERT_THROW((pfd_freq >= dbsrx_pfd_freq_range.start()) and (pfd_freq <= dbsrx_pfd_freq_range.stop()));      UHD_ASSERT_THROW((N >= 256) and (N <= 32768)); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("DBSRX") << boost::format(          "DBSRX: choose ref_clock (current: %f, new: %f) and m_divider %d" -    ) % (this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX)) % ref_clock % m << std::endl; +    ) % (this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX)) % ref_clock % m ;      //if ref_clock or m divider changed, we need to update the filter settings      if (ref_clock != this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX) or m != _max2118_write_regs.m_divider) update_filter_settings = true; @@ -337,9 +337,9 @@ double dbsrx::set_lo_freq(double target_freq){      int scaler = actual_freq > 1125e6 ? 2 : 4;      _max2118_write_regs.div2 = scaler == 4 ? max2118_write_regs_t::DIV2_DIV4 : max2118_write_regs_t::DIV2_DIV2; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("DBSRX") << boost::format(          "DBSRX: scaler %d, actual_freq %f MHz, register bit: %d" -    ) % scaler % (actual_freq/1e6) % int(_max2118_write_regs.div2) << std::endl; +    ) % scaler % (actual_freq/1e6) % int(_max2118_write_regs.div2) ;      //compute vco frequency and select vco      double vco_freq = actual_freq * scaler; @@ -366,9 +366,9 @@ double dbsrx::set_lo_freq(double target_freq){      //check vtune for lock condition      read_reg(0x0, 0x0); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("DBSRX") << boost::format(          "DBSRX: initial guess for vco %d, vtune adc %d" -    ) % int(_max2118_write_regs.osc_band) % int(_max2118_read_regs.adc) << std::endl; +    ) % int(_max2118_write_regs.osc_band) % int(_max2118_read_regs.adc) ;      //if we are out of lock for chosen vco, change vco      while ((_max2118_read_regs.adc == 0) or (_max2118_read_regs.adc == 7)){ @@ -376,7 +376,7 @@ double dbsrx::set_lo_freq(double target_freq){          //vtune is too low, try lower frequency vco          if (_max2118_read_regs.adc == 0){              if (_max2118_write_regs.osc_band == 0){ -                UHD_MSG(warning) << boost::format( +                UHD_LOGGER_WARNING("DBSRX") << boost::format(                          "DBSRX: Tuning exceeded vco range, _max2118_write_regs.osc_band == %d\n"                          ) % int(_max2118_write_regs.osc_band);                  UHD_ASSERT_THROW(_max2118_read_regs.adc != 0); //just to cause a throw @@ -388,7 +388,7 @@ double dbsrx::set_lo_freq(double target_freq){          //vtune is too high, try higher frequency vco          if (_max2118_read_regs.adc == 7){              if (_max2118_write_regs.osc_band == 7){ -                UHD_MSG(warning) << boost::format( +                UHD_LOGGER_WARNING("DBSRX") << boost::format(                          "DBSRX: Tuning exceeded vco range, _max2118_write_regs.osc_band == %d\n"                          ) % int(_max2118_write_regs.osc_band);                  UHD_ASSERT_THROW(_max2118_read_regs.adc != 7); //just to cause a throw @@ -397,9 +397,9 @@ double dbsrx::set_lo_freq(double target_freq){              _max2118_write_regs.osc_band += 1;          } -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("DBSRX") << boost::format(              "DBSRX: trying vco %d, vtune adc %d" -        ) % int(_max2118_write_regs.osc_band) % int(_max2118_read_regs.adc) << std::endl; +        ) % int(_max2118_write_regs.osc_band) % int(_max2118_read_regs.adc) ;          //update vco selection and check vtune          send_reg(0x2, 0x2); @@ -409,9 +409,9 @@ double dbsrx::set_lo_freq(double target_freq){          boost::this_thread::sleep(boost::posix_time::milliseconds(10));      } -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("DBSRX") << boost::format(          "DBSRX: final vco %d, vtune adc %d" -    ) % int(_max2118_write_regs.osc_band) % int(_max2118_read_regs.adc) << std::endl; +    ) % int(_max2118_write_regs.osc_band) % int(_max2118_read_regs.adc) ;      //select charge pump bias current      if (_max2118_read_regs.adc <= 2) _max2118_write_regs.cp_current = max2118_write_regs_t::CP_CURRENT_I_CP_100UA; @@ -425,7 +425,7 @@ double dbsrx::set_lo_freq(double target_freq){      _lo_freq = this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX) / std::pow(2.0,(1 + _max2118_write_regs.r_divider)) * _max2118_write_regs.get_n_divider();      //debug output of calculated variables -    UHD_LOGV(often) +    UHD_LOGGER_TRACE("DBSRX")          << boost::format("DBSRX tune:\n")          << boost::format("    VCO=%d, CP=%d, PFD Freq=%fMHz\n") % int(_max2118_write_regs.osc_band) % _max2118_write_regs.cp_current % (pfd_freq/1e6)          << boost::format("    R=%d, N=%f, scaler=%d, div2=%d\n") % R % N % scaler % int(_max2118_write_regs.div2) @@ -433,7 +433,7 @@ double dbsrx::set_lo_freq(double target_freq){          << boost::format("    Target Freq=%fMHz\n") % (target_freq/1e6)          << boost::format("    Actual Freq=%fMHz\n") % (_lo_freq/1e6)          << boost::format("    VCO    Freq=%fMHz\n") % (vco_freq/1e6) -        << std::endl; +        ;      if (update_filter_settings) set_bandwidth(_bandwidth);      get_locked(); @@ -463,9 +463,9 @@ static int gain_to_gc2_vga_reg(double &gain){          gain = double(boost::math::iround(gain));      } -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("DBSRX") << boost::format(          "DBSRX GC2 Gain: %f dB, reg: %d" -    ) % gain % reg << std::endl; +    ) % gain % reg ;      return reg;  } @@ -487,9 +487,9 @@ static double gain_to_gc1_rfvga_dac(double &gain){      //calculate the voltage for the aux dac      double dac_volts = gain*slope + min_volts; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("DBSRX") << boost::format(          "DBSRX GC1 Gain: %f dB, dac_volts: %f V" -    ) % gain % dac_volts << std::endl; +    ) % gain % dac_volts ;      //the actual gain setting      gain = (dac_volts - min_volts)/slope; @@ -533,9 +533,9 @@ double dbsrx::set_bandwidth(double bandwidth){      //determine actual bandwidth      _bandwidth = double((ref_clock/(_max2118_write_regs.m_divider))*(4+0.145*_max2118_write_regs.f_dac)); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("DBSRX") << boost::format(          "DBSRX Filter Bandwidth: %f MHz, m: %d, f_dac: %d\n" -    ) % (_bandwidth/1e6) % int(_max2118_write_regs.m_divider) % int(_max2118_write_regs.f_dac) << std::endl; +    ) % (_bandwidth/1e6) % int(_max2118_write_regs.m_divider) % int(_max2118_write_regs.f_dac) ;      this->send_reg(0x3, 0x4); diff --git a/host/lib/usrp/dboard/db_dbsrx2.cpp b/host/lib/usrp/dboard/db_dbsrx2.cpp index 21b0fd02d..8cc209218 100644 --- a/host/lib/usrp/dboard/db_dbsrx2.cpp +++ b/host/lib/usrp/dboard/db_dbsrx2.cpp @@ -92,9 +92,9 @@ private:              //get the register data              for(int i=0; i<num_bytes; i++){                  regs_vector[1+i] = _max2112_write_regs.get_reg(start_addr+i); -                UHD_LOGV(often) << boost::format( +                UHD_LOGGER_TRACE("DBSRX") << boost::format(                      "DBSRX2: send reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" -                ) % int(start_addr+i) % int(regs_vector[1+i]) % int(start_addr) % num_bytes << std::endl; +                ) % int(start_addr+i) % int(regs_vector[1+i]) % int(start_addr) % num_bytes ;              }              //send the data @@ -132,15 +132,10 @@ private:              for(uint8_t i=0; i < num_bytes; i++){                  if (i + start_addr >= status_addr){                      _max2112_read_regs.set_reg(i + start_addr, regs_vector[i]); -                    /* -                    UHD_LOGV(always) << boost::format( -                        "DBSRX2: set reg 0x%02x, value 0x%04x" -                    ) % int(i + start_addr) % int(_max2112_read_regs.get_reg(i + start_addr)) << std::endl; -                    */                  } -                UHD_LOGV(often) << boost::format( +                UHD_LOGGER_TRACE("DBSRX") << boost::format(                      "DBSRX2: read reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" -                ) % int(start_addr+i) % int(regs_vector[i]) % int(start_addr) % num_bytes << std::endl; +                ) % int(start_addr+i) % int(regs_vector[i]) % int(start_addr) % num_bytes ;              }          }      } @@ -155,9 +150,9 @@ private:          //mask and return lock detect          bool locked = (_max2112_read_regs.ld & _max2112_read_regs.vasa & _max2112_read_regs.vase) != 0; -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("DBSRX") << boost::format(              "DBSRX2 locked: %d" -        ) % locked << std::endl; +        ) % locked ;          return sensor_value_t("LO", locked, "locked", "unlocked");      } @@ -189,10 +184,10 @@ dbsrx2::dbsrx2(ctor_args_t args) : rx_dboard_base(args){      // Register properties      ////////////////////////////////////////////////////////////////////      this->get_rx_subtree()->create<std::string>("name") -        .set("DBSRX2"); +        .set("DBSRX");      this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked")          .set_publisher(boost::bind(&dbsrx2::get_locked, this)); -    BOOST_FOREACH(const std::string &name, dbsrx2_gain_ranges.keys()){ +    for(const std::string &name:  dbsrx2_gain_ranges.keys()){          this->get_rx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&dbsrx2::set_gain, this, _1, name))              .set(dbsrx2_gain_ranges[name].start()); @@ -270,14 +265,14 @@ double dbsrx2::set_lo_freq(double target_freq){      _max2112_write_regs.d24 = scaler == 4 ? max2112_write_regs_t::D24_DIV4 : max2112_write_regs_t::D24_DIV2;      //debug output of calculated variables -    UHD_LOGV(often) +    UHD_LOGGER_TRACE("DBSRX")          << boost::format("DBSRX2 tune:\n")          << boost::format("    R=%d, N=%f, scaler=%d, ext_div=%d\n") % R % N % scaler % ext_div          << boost::format("    int=%d, frac=%d, d24=%d\n") % intdiv % fracdiv % int(_max2112_write_regs.d24)          << boost::format("    Ref    Freq=%fMHz\n") % (ref_freq/1e6)          << boost::format("    Target Freq=%fMHz\n") % (target_freq/1e6)          << boost::format("    Actual Freq=%fMHz\n") % (_lo_freq/1e6) -        << std::endl; +        ;      //send the registers 0x0 through 0x7      //writing register 0x4 (F divider LSB) starts the VCO auto seletion so it must be written last @@ -304,10 +299,10 @@ static int gain_to_bbg_vga_reg(double &gain){      gain = double(reg); -    UHD_LOGV(often) +    UHD_LOGGER_TRACE("DBSRX")          << boost::format("DBSRX2 BBG Gain:\n")          << boost::format("    %f dB, bbg: %d") % gain % reg -        << std::endl; +    ;      return reg;  } @@ -329,10 +324,10 @@ static double gain_to_gc1_rfvga_dac(double &gain){      //calculate the voltage for the aux dac      double dac_volts = gain*slope + min_volts; -    UHD_LOGV(often) +    UHD_LOGGER_TRACE("DBSRX")          << boost::format("DBSRX2 GC1 Gain:\n")          << boost::format("    %f dB, dac_volts: %f V") % gain % dac_volts -        << std::endl; +        ;      //the actual gain setting      gain = (dac_volts - min_volts)/slope; @@ -369,10 +364,10 @@ double dbsrx2::set_bandwidth(double bandwidth){      _max2112_write_regs.lp = int((bandwidth/1e6 - 4)/0.29 + 12);      _bandwidth = double(4 + (_max2112_write_regs.lp - 12) * 0.29)*1e6; -    UHD_LOGV(often) +    UHD_LOGGER_TRACE("DBSRX")          << boost::format("DBSRX2 Bandwidth:\n")          << boost::format("    %f MHz, lp: %f V") % (_bandwidth/1e6) % int(_max2112_write_regs.lp) -        << std::endl; +    ;      this->send_reg(0x8, 0x8); diff --git a/host/lib/usrp/dboard/db_rfx.cpp b/host/lib/usrp/dboard/db_rfx.cpp index 9bbd73425..e8ceb7d49 100644 --- a/host/lib/usrp/dboard/db_rfx.cpp +++ b/host/lib/usrp/dboard/db_rfx.cpp @@ -40,7 +40,7 @@  #include <uhd/utils/log.hpp>  #include <uhd/utils/static.hpp>  #include <uhd/utils/algorithm.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/usrp/dboard_id.hpp>  #include <uhd/usrp/dboard_base.hpp>  #include <uhd/usrp/dboard_manager.hpp> @@ -184,7 +184,7 @@ rfx_xcvr::rfx_xcvr(      this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked")          .set_publisher(boost::bind(&rfx_xcvr::get_locked, this, dboard_iface::UNIT_RX)); -    BOOST_FOREACH(const std::string &name, _rx_gain_ranges.keys()){ +    for(const std::string &name:  _rx_gain_ranges.keys()){          this->get_rx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&rfx_xcvr::set_rx_gain, this, _1, name))              .set(_rx_gain_ranges[name].start()); @@ -339,9 +339,9 @@ double rfx_xcvr::set_lo_freq(      dboard_iface::unit_t unit,      double target_freq  ){ -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("RFX") << boost::format(          "RFX tune: target frequency %f MHz" -    ) % (target_freq/1e6) << std::endl; +    ) % (target_freq/1e6) ;      //clip the input      target_freq = _freq_range.clip(target_freq); @@ -379,9 +379,9 @@ double rfx_xcvr::set_lo_freq(       * fvco*R/fref = P*B + A = N       */      for(R = 2; R <= 32; R+=2){ -        BOOST_FOREACH(BS, bandsel_to_enum.keys()){ +        for(auto BS:  bandsel_to_enum.keys()){              if (ref_freq/R/BS > 1e6) continue; //constraint on band select clock -            BOOST_FOREACH(P, prescaler_to_enum.keys()){ +            for(auto P:  prescaler_to_enum.keys()){                  //calculate B and A from N                  double N = target_freq*R/ref_freq;                  B = int(std::floor(N/P)); @@ -396,9 +396,9 @@ double rfx_xcvr::set_lo_freq(          }      } done_loop: -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("RFX") << boost::format(          "RFX tune: R=%d, BS=%d, P=%d, B=%d, A=%d, DIV2=%d" -    ) % R % BS % P % B % A % int(_div2[unit] && (!is_rx_rfx400)) << std::endl; +    ) % R % BS % P % B % A % int(_div2[unit] && (!is_rx_rfx400)) ;      //load the register values      adf4360_regs_t regs; @@ -433,7 +433,7 @@ double rfx_xcvr::set_lo_freq(          (adf4360_regs_t::ADDR_CONTROL)          (adf4360_regs_t::ADDR_NCOUNTER)      ; -    BOOST_FOREACH(adf4360_regs_t::addr_t addr, addrs){ +    for(adf4360_regs_t::addr_t addr:  addrs){          this->get_iface()->write_spi(              unit, spi_config_t::EDGE_RISE,              regs.get_reg(addr), 24 @@ -442,8 +442,8 @@ double rfx_xcvr::set_lo_freq(      //return the actual frequency      if (_div2[unit]) actual_freq /= 2; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("RFX") << boost::format(          "RFX tune: actual frequency %f MHz" -    ) % (actual_freq/1e6) << std::endl; +    ) % (actual_freq/1e6) ;      return actual_freq;  } diff --git a/host/lib/usrp/dboard/db_sbx_common.cpp b/host/lib/usrp/dboard/db_sbx_common.cpp index efc84d7e6..8df4028e7 100644 --- a/host/lib/usrp/dboard/db_sbx_common.cpp +++ b/host/lib/usrp/dboard/db_sbx_common.cpp @@ -53,9 +53,9 @@ static int rx_pga0_gain_to_iobits(double &gain){      int attn_code = int(floor(attn*2));      int iobits = ((~attn_code) << RX_ATTN_SHIFT) & RX_ATTN_MASK; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("SBX") << boost::format(          "SBX RX Attenuation: %f dB, Code: %d, IO Bits %x, Mask: %x" -    ) % attn % attn_code % (iobits & RX_ATTN_MASK) % RX_ATTN_MASK << std::endl; +    ) % attn % attn_code % (iobits & RX_ATTN_MASK) % RX_ATTN_MASK ;      //the actual gain setting      gain = sbx_rx_gain_ranges["PGA0"].stop() - double(attn_code)/2; @@ -74,9 +74,9 @@ static int tx_pga0_gain_to_iobits(double &gain){      int attn_code = int(floor(attn*2));      int iobits = ((~attn_code) << TX_ATTN_SHIFT) & TX_ATTN_MASK; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("SBX") << boost::format(          "SBX TX Attenuation: %f dB, Code: %d, IO Bits %x, Mask: %x" -    ) % attn % attn_code % (iobits & TX_ATTN_MASK) % TX_ATTN_MASK << std::endl; +    ) % attn % attn_code % (iobits & TX_ATTN_MASK) % TX_ATTN_MASK ;      //the actual gain setting      gain = sbx_tx_gain_ranges["PGA0"].stop() - double(attn_code)/2; @@ -160,7 +160,7 @@ sbx_xcvr::sbx_xcvr(ctor_args_t args) : xcvr_dboard_base(args){      this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked")          .set_publisher(boost::bind(&sbx_xcvr::get_locked, this, dboard_iface::UNIT_RX)); -    BOOST_FOREACH(const std::string &name, sbx_rx_gain_ranges.keys()){ +    for(const std::string &name:  sbx_rx_gain_ranges.keys()){          this->get_rx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&sbx_xcvr::set_rx_gain, this, _1, name))              .set(sbx_rx_gain_ranges[name].start()); @@ -201,7 +201,7 @@ sbx_xcvr::sbx_xcvr(ctor_args_t args) : xcvr_dboard_base(args){      this->get_tx_subtree()->create<sensor_value_t>("sensors/lo_locked")          .set_publisher(boost::bind(&sbx_xcvr::get_locked, this, dboard_iface::UNIT_TX)); -    BOOST_FOREACH(const std::string &name, sbx_tx_gain_ranges.keys()){ +    for(const std::string &name:  sbx_tx_gain_ranges.keys()){          this->get_tx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&sbx_xcvr::set_tx_gain, this, _1, name))              .set(sbx_tx_gain_ranges[name].start()); @@ -240,9 +240,9 @@ sbx_xcvr::sbx_xcvr(ctor_args_t args) : xcvr_dboard_base(args){      //Initialize ATR registers after direction and pin ctrl configuration      update_atr(); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("SBX") << boost::format(          "SBX GPIO Direction: RX: 0x%08x, TX: 0x%08x" -    ) % RXIO_MASK % TXIO_MASK << std::endl; +    ) % RXIO_MASK % TXIO_MASK ;  }  sbx_xcvr::~sbx_xcvr(void){ diff --git a/host/lib/usrp/dboard/db_sbx_common.hpp b/host/lib/usrp/dboard/db_sbx_common.hpp index ad64e2267..0e4dc5ace 100644 --- a/host/lib/usrp/dboard/db_sbx_common.hpp +++ b/host/lib/usrp/dboard/db_sbx_common.hpp @@ -84,7 +84,7 @@  #include <uhd/utils/log.hpp>  #include <uhd/utils/static.hpp>  #include <uhd/utils/algorithm.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/usrp/dboard_base.hpp>  #include <uhd/usrp/dboard_manager.hpp>  #include <boost/assign/list_of.hpp> diff --git a/host/lib/usrp/dboard/db_sbx_version3.cpp b/host/lib/usrp/dboard/db_sbx_version3.cpp index bb2ba6bd6..f35c09946 100644 --- a/host/lib/usrp/dboard/db_sbx_version3.cpp +++ b/host/lib/usrp/dboard/db_sbx_version3.cpp @@ -40,7 +40,7 @@ sbx_xcvr::sbx_version3::~sbx_version3(void){  void sbx_xcvr::sbx_version3::write_lo_regs(dboard_iface::unit_t unit, const std::vector<uint32_t> ®s)  { -    BOOST_FOREACH(uint32_t reg, regs) +    for(uint32_t reg:  regs)      {          self_base->get_iface()->write_spi(unit, spi_config_t::EDGE_RISE, reg, 32);      } @@ -50,9 +50,9 @@ void sbx_xcvr::sbx_version3::write_lo_regs(dboard_iface::unit_t unit, const std:   * Tuning   **********************************************************************/  double sbx_xcvr::sbx_version3::set_lo_freq(dboard_iface::unit_t unit, double target_freq) { -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("SBX") << boost::format(          "SBX tune: target frequency %f MHz" -    ) % (target_freq/1e6) << std::endl; +    ) % (target_freq/1e6) ;      /*       * If the user sets 'mode_n=integer' in the tuning args, the user wishes to diff --git a/host/lib/usrp/dboard/db_sbx_version4.cpp b/host/lib/usrp/dboard/db_sbx_version4.cpp index e5b6e081c..746de780b 100644 --- a/host/lib/usrp/dboard/db_sbx_version4.cpp +++ b/host/lib/usrp/dboard/db_sbx_version4.cpp @@ -41,7 +41,7 @@ sbx_xcvr::sbx_version4::~sbx_version4(void){  void sbx_xcvr::sbx_version4::write_lo_regs(dboard_iface::unit_t unit, const std::vector<uint32_t> ®s)  { -    BOOST_FOREACH(uint32_t reg, regs) +    for(uint32_t reg:  regs)      {          self_base->get_iface()->write_spi(unit, spi_config_t::EDGE_RISE, reg, 32);      } @@ -52,9 +52,9 @@ void sbx_xcvr::sbx_version4::write_lo_regs(dboard_iface::unit_t unit, const std:   * Tuning   **********************************************************************/  double sbx_xcvr::sbx_version4::set_lo_freq(dboard_iface::unit_t unit, double target_freq) { -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("SBX") << boost::format(          "SBX tune: target frequency %f MHz" -    ) % (target_freq/1e6) << std::endl; +    ) % (target_freq/1e6) ;      /*       * If the user sets 'mode_n=integer' in the tuning args, the user wishes to diff --git a/host/lib/usrp/dboard/db_tvrx.cpp b/host/lib/usrp/dboard/db_tvrx.cpp index 5c0600c61..bae047bbd 100644 --- a/host/lib/usrp/dboard/db_tvrx.cpp +++ b/host/lib/usrp/dboard/db_tvrx.cpp @@ -31,7 +31,7 @@  #include <uhd/utils/static.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/algorithm.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/types/ranges.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/types/dict.hpp> @@ -107,7 +107,7 @@ static const boost::array<double, 17> tvrx_gains_volts =  static uhd::dict<std::string, gain_range_t> get_tvrx_gain_ranges(void) {      double rfmax = 0.0, rfmin = FLT_MAX; -    BOOST_FOREACH(const std::string range, tvrx_rf_gains_db.keys()) { +    for(const std::string range:  tvrx_rf_gains_db.keys()) {          double my_max = tvrx_rf_gains_db[range].back(); //we're assuming it's monotonic          double my_min = tvrx_rf_gains_db[range].front(); //if it's not this is wrong wrong wrong          if(my_max > rfmax) rfmax = my_max; @@ -153,9 +153,9 @@ private:          //get the register data          for(int i=0; i<4; i++){              regs_vector[i] = _tuner_4937di5_regs.get_reg(i); -            UHD_LOGV(often) << boost::format( +            UHD_LOGGER_TRACE("TVRX") << boost::format(                  "tvrx: send reg 0x%02x, value 0x%04x" -            ) % int(i) % int(regs_vector[i]) << std::endl; +            ) % int(i) % int(regs_vector[i]) ;          }          //send the data @@ -188,7 +188,7 @@ tvrx::tvrx(ctor_args_t args) : rx_dboard_base(args){      this->get_rx_subtree()->create<std::string>("name")          .set("TVRX");      this->get_rx_subtree()->create<int>("sensors"); //phony property so this dir exists -    BOOST_FOREACH(const std::string &name, get_tvrx_gain_ranges().keys()){ +    for(const std::string &name:  get_tvrx_gain_ranges().keys()){          this->get_rx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&tvrx::set_gain, this, _1, name));          this->get_rx_subtree()->create<meta_range_t>("gains/"+name+"/range") @@ -232,7 +232,7 @@ tvrx::tvrx(ctor_args_t args) : rx_dboard_base(args){      this->get_rx_subtree()->access<double>("freq/value").set(tvrx_freq_range.start());      //set default gains -    BOOST_FOREACH(const std::string &name, get_tvrx_gain_ranges().keys()){ +    for(const std::string &name:  get_tvrx_gain_ranges().keys()){          this->get_rx_subtree()->access<double>("gains/"+name+"/value")              .set(get_tvrx_gain_ranges()[name].start());      } @@ -247,9 +247,9 @@ tvrx::~tvrx(void){   */  static std::string get_band(double freq) { -    BOOST_FOREACH(const std::string &band, tvrx_freq_ranges.keys()) { +    for(const std::string &band:  tvrx_freq_ranges.keys()) {          if(freq >= tvrx_freq_ranges[band].start() && freq <= tvrx_freq_ranges[band].stop()){ -            UHD_LOGV(often) << "Band: " << band << std::endl; +            UHD_LOGGER_TRACE("TVRX") << "Band: " << band ;              return band;          }      } @@ -291,7 +291,7 @@ static double gain_interp(double gain, const boost::array<double, 17>& db_vector      //use the volts per dB slope to find the final interpolated voltage      volts = volts_vector[gain_step] + (slope * (gain - db_vector[gain_step])); -    UHD_LOGV(often) << "Gain interp: gain: " << gain << ", gain_step: " << int(gain_step) << ", slope: " << slope << ", volts: " << volts << std::endl; +    UHD_LOGGER_TRACE("TVRX") << "Gain interp: gain: " << gain << ", gain_step: " << int(gain_step) << ", slope: " << slope << ", volts: " << volts ;      return volts;  } @@ -317,9 +317,9 @@ static double rf_gain_to_voltage(double gain, double lo_freq){      dac_volts = uhd::clip<double>(dac_volts, 0.0, 3.3); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("TVRX") << boost::format(          "tvrx RF AGC gain: %f dB, dac_volts: %f V" -    ) % gain % dac_volts << std::endl; +    ) % gain % dac_volts ;      return dac_volts;  } @@ -340,9 +340,9 @@ static double if_gain_to_voltage(double gain){      dac_volts = uhd::clip<double>(dac_volts, 0.0, 3.3); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("TVRX") << boost::format(          "tvrx IF AGC gain: %f dB, dac_volts: %f V" -    ) % gain % dac_volts << std::endl; +    ) % gain % dac_volts ;      return dac_volts;  } @@ -396,7 +396,7 @@ double tvrx::set_freq(double freq) {      //not FAR off, but we do this to be consistent      if(prev_band != new_band) set_gain(_gains["RF"], "RF"); -    UHD_LOGV(often) << boost::format("set_freq: target LO: %f f_ref: %f divisor: %i actual LO: %f") % target_lo_freq % f_ref % divisor % actual_lo_freq << std::endl; +    UHD_LOGGER_TRACE("TVRX") << boost::format("set_freq: target LO: %f f_ref: %f divisor: %i actual LO: %f") % target_lo_freq % f_ref % divisor % actual_lo_freq ;      _lo_freq = actual_lo_freq; //for rx props diff --git a/host/lib/usrp/dboard/db_tvrx2.cpp b/host/lib/usrp/dboard/db_tvrx2.cpp index 1bac81153..2b5524069 100644 --- a/host/lib/usrp/dboard/db_tvrx2.cpp +++ b/host/lib/usrp/dboard/db_tvrx2.cpp @@ -52,7 +52,7 @@  #include "tda18272hnm_regs.hpp"  #include <uhd/utils/static.hpp>  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/utils/safe_call.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/algorithm.hpp> @@ -803,9 +803,9 @@ private:          //return irq status          bool irq = _tda18272hnm_regs.irq_status == tda18272hnm_regs_t::IRQ_STATUS_SET; -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("TVRX") << boost::format(              "TVRX2 (%s): IRQ %d" -        ) % (get_subdev_name()) % irq << std::endl; +        ) % (get_subdev_name()) % irq ;          return irq;      } @@ -821,9 +821,9 @@ private:          //return POR state          bool por = _tda18272hnm_regs.por == tda18272hnm_regs_t::POR_RESET; -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("TVRX") << boost::format(              "TVRX2 (%s): POR %d" -        ) % (get_subdev_name()) % int(_tda18272hnm_regs.por) << std::endl; +        ) % (get_subdev_name()) % int(_tda18272hnm_regs.por) ;          return por;      } @@ -838,9 +838,9 @@ private:          //return lock detect          bool locked = _tda18272hnm_regs.lo_lock == tda18272hnm_regs_t::LO_LOCK_LOCKED; -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("TVRX") << boost::format(              "TVRX2 (%s): locked %d" -        ) % (get_subdev_name()) % locked << std::endl; +        ) % (get_subdev_name()) % locked ;          return sensor_value_t("LO", locked, "locked", "unlocked");      } @@ -881,9 +881,9 @@ private:          //read temp in degC          read_reg(0x3, 0x3); -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("TVRX") << boost::format(              "TVRX2 (%s): Temperature %f C" -        ) % (get_subdev_name()) % (double(_tda18272hnm_regs.tm_d)) << std::endl; +        ) % (get_subdev_name()) % (double(_tda18272hnm_regs.tm_d)) ;          //Disable Temperature reading          _tda18272hnm_regs.tm_on = tda18272hnm_regs_t::TM_ON_SENSOR_OFF; @@ -962,7 +962,7 @@ tvrx2::tvrx2(ctor_args_t args) : rx_dboard_base(args){          .set_publisher(boost::bind(&tvrx2::get_rssi, this));      this->get_rx_subtree()->create<sensor_value_t>("sensors/temperature")          .set_publisher(boost::bind(&tvrx2::get_temp, this)); -    BOOST_FOREACH(const std::string &name, tvrx2_gain_ranges.keys()){ +    for(const std::string &name:  tvrx2_gain_ranges.keys()){          this->get_rx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&tvrx2::set_gain, this, _1, name));          this->get_rx_subtree()->create<meta_range_t>("gains/"+name+"/range") @@ -999,42 +999,42 @@ tvrx2::tvrx2(ctor_args_t args) : rx_dboard_base(args){      if (ref_clock == 64.0e6) {          this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, REFCLOCK_DIV4); -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("TVRX") << boost::format(              "TVRX2 (%s): Dividing Refclock by 4" -        ) % (get_subdev_name()) << std::endl; +        ) % (get_subdev_name()) ;          _freq_scalar = (4*16.0e6)/(this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX));      } else if (ref_clock == 100e6) {          this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, REFCLOCK_DIV6); -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("TVRX") << boost::format(              "TVRX2 (%s): Dividing Refclock by 6" -        ) % (get_subdev_name()) << std::endl; +        ) % (get_subdev_name()) ;          _freq_scalar = (6*16.0e6)/this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX);      } else if (ref_clock == 200e6)  { -        UHD_MSG(warning) << boost::format("ref_clock was 200e6, setting ref_clock divider for 100e6.") << std::endl; +        UHD_LOGGER_WARNING("TVRX") << boost::format("ref_clock was 200e6, setting ref_clock divider for 100e6.") ;          this->get_iface()->set_clock_rate(dboard_iface::UNIT_RX, 100e6);          this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, REFCLOCK_DIV6); -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("TVRX") << boost::format(              "TVRX2 (%s): Dividing Refclock by 6" -        ) % (get_subdev_name()) << std::endl; +        ) % (get_subdev_name()) ;          _freq_scalar = (6*16.0e6)/this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX);      } else {          this->get_iface()->set_gpio_out(dboard_iface::UNIT_RX, REFCLOCK_DIV6); -        UHD_MSG(warning) << boost::format("Unsupported ref_clock %0.2f, valid options 64e6, 100e6, 200e6") % ref_clock << std::endl; +        UHD_LOGGER_WARNING("TVRX") << boost::format("Unsupported ref_clock %0.2f, valid options 64e6, 100e6, 200e6") % ref_clock ;          _freq_scalar = 1.0;      }      //enable only the clocks we need      this->get_iface()->set_clock_enabled(dboard_iface::UNIT_RX, true); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("TVRX") << boost::format(          "TVRX2 (%s): Refclock %f Hz, scalar = %f" -    ) % (get_subdev_name()) % (this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX)) % _freq_scalar << std::endl; +    ) % (get_subdev_name()) % (this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX)) % _freq_scalar ;      _tda18272hnm_regs.irq_polarity = tda18272hnm_regs_t::IRQ_POLARITY_RAISED_VCC;      _tda18272hnm_regs.irq_clear = tda18272hnm_regs_t::IRQ_CLEAR_TRUE; @@ -1066,7 +1066,7 @@ bool tvrx2::set_enabled(bool enable){          test_rf_filter_robustness(); -        BOOST_FOREACH(const std::string &name, tvrx2_gain_ranges.keys()){ +        for(const std::string &name:  tvrx2_gain_ranges.keys()){              this->get_rx_subtree()->access<double>("gains/"+name+"/value")                  .set(tvrx2_gain_ranges[name].start());          } @@ -1092,9 +1092,9 @@ bool tvrx2::set_enabled(bool enable){  }  tvrx2::~tvrx2(void){ -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("TVRX") << boost::format(          "TVRX2 (%s): Called Destructor" -    ) % (get_subdev_name()) << std::endl; +    ) % (get_subdev_name()) ;      UHD_SAFE_CALL(if (_enabled) set_enabled(false);)  } @@ -1134,9 +1134,9 @@ void tvrx2::send_reg(uint8_t start_reg, uint8_t stop_reg){          //get the register data          for(int i=0; i<num_bytes; i++){              regs_vector[1+i] = _tda18272hnm_regs.get_reg(start_addr+i); -            UHD_LOGV(often) << boost::format( +            UHD_LOGGER_TRACE("TVRX") << boost::format(                  "TVRX2 (%s, 0x%02x): send reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" -            ) % (get_subdev_name()) % int(tvrx2_sd_name_to_i2c_addr[get_subdev_name()]) % int(start_addr+i) % int(regs_vector[1+i]) % int(start_addr) % num_bytes << std::endl; +            ) % (get_subdev_name()) % int(tvrx2_sd_name_to_i2c_addr[get_subdev_name()]) % int(start_addr+i) % int(regs_vector[1+i]) % int(start_addr) % num_bytes ;          }          //send the data @@ -1177,9 +1177,9 @@ void tvrx2::read_reg(uint8_t start_reg, uint8_t stop_reg){              if (i + start_addr >= status_addr){                  _tda18272hnm_regs.set_reg(i + start_addr, regs_vector[i]);              } -            UHD_LOGV(often) << boost::format( +            UHD_LOGGER_TRACE("TVRX") << boost::format(                  "TVRX2 (%s, 0x%02x): read reg 0x%02x, value 0x%04x, start_addr = 0x%04x, num_bytes %d" -            ) % (get_subdev_name()) % int(tvrx2_sd_name_to_i2c_addr[get_subdev_name()]) % int(start_addr+i) % int(regs_vector[i]) % int(start_addr) % num_bytes << std::endl; +            ) % (get_subdev_name()) % int(tvrx2_sd_name_to_i2c_addr[get_subdev_name()]) % int(start_addr+i) % int(regs_vector[i]) % int(start_addr) % num_bytes ;          }      }  } @@ -1271,14 +1271,14 @@ void tvrx2::tvrx2_tda18272_init_rfcal(void)      // Loop through rfcal_log_* registers, initialize _rfcal_results -    BOOST_FOREACH(const uint32_t &result, result_to_cal_regs.keys()) +    for(const uint32_t &result:  result_to_cal_regs.keys())          _rfcal_results[result].delta_c = result_to_cal_regs[result] > 63 ? result_to_cal_regs[result] - 128 : result_to_cal_regs[result];      /* read byte 0x26-0x2B */      read_reg(0x26, 0x2B);      // Loop through rfcal_byte_* registers, initialize _rfcal_coeffs -    BOOST_FOREACH(const uint32_t &subband, _rfcal_coeffs.keys()) +    for(const uint32_t &subband:  _rfcal_coeffs.keys())      {          freq_range_t subband_freqs; @@ -1374,7 +1374,7 @@ void tvrx2::tvrx2_tda18272_tune_rf_filter(uint32_t uRF)      _tda18272hnm_regs.gain_taper = gain_taper;      _tda18272hnm_regs.rf_filter_band = RFBand; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("TVRX") << boost::format(          "\nTVRX2 (%s): Software Calibration:\n"          "\tRF Filter Bypass = %d\n"          "\tRF Filter Cap    = %d\n" @@ -1385,14 +1385,14 @@ void tvrx2::tvrx2_tda18272_tune_rf_filter(uint32_t uRF)          % int(_tda18272hnm_regs.rf_filter_cap)          % int(_tda18272hnm_regs.rf_filter_band)           % int(_tda18272hnm_regs.gain_taper) -        << std::endl; +        ;      send_reg(0x2c, 0x2f);  }  void tvrx2::soft_calibration(void){ -    UHD_LOGV(often) << boost::format( -        "\nTVRX2 (%s): Software Calibration: Initialize Tuner, Calibrate and Standby\n") % (get_subdev_name()) << std::endl; +    UHD_LOGGER_TRACE("TVRX") << boost::format( +        "\nTVRX2 (%s): Software Calibration: Initialize Tuner, Calibrate and Standby\n") % (get_subdev_name()) ;      _tda18272hnm_regs.sm = tda18272hnm_regs_t::SM_NORMAL;      _tda18272hnm_regs.sm_lna = tda18272hnm_regs_t::SM_LNA_ON; @@ -1473,7 +1473,7 @@ void tvrx2::test_rf_filter_robustness(void){          ("UHFHigh_1", 0x43)      ; -    BOOST_FOREACH(const std::string &name, filter_cal_regs.keys()){ +    for(const std::string &name:  filter_cal_regs.keys()){          uint8_t cal_result = _tda18272hnm_regs.get_reg(filter_cal_regs[name]);          if (cal_result & 0x80) {              _filter_ratings.set(name, "E"); @@ -1515,12 +1515,12 @@ void tvrx2::test_rf_filter_robustness(void){      }      std::stringstream robustness_message; -    robustness_message << boost::format("TVRX2 (%s): RF Filter Robustness Results:") % (get_subdev_name()) << std::endl; -    BOOST_FOREACH(const std::string &name, uhd::sorted(_filter_ratings.keys())){ -        robustness_message << boost::format("\t%s:\tMargin = %0.2f,\tRobustness = %c") % name % (_filter_margins[name]) % (_filter_ratings[name]) << std::endl; +    robustness_message << boost::format("TVRX2 (%s): RF Filter Robustness Results:") % (get_subdev_name()); +    for(const std::string &name:  uhd::sorted(_filter_ratings.keys())){ +        robustness_message << boost::format("\t%s:\tMargin = %0.2f,\tRobustness = %c") % name % (_filter_margins[name]) % (_filter_ratings[name]);      } -    UHD_LOGV(often) << robustness_message.str(); +    UHD_LOGGER_DEBUG("TVRX") << robustness_message.str();  }  /*********************************************************************** @@ -1528,8 +1528,8 @@ void tvrx2::test_rf_filter_robustness(void){   **********************************************************************/  void tvrx2::transition_0(void){      //Transition 0: Initialize Tuner and place in standby -    UHD_LOGV(often) << boost::format( -        "\nTVRX2 (%s): Transition 0: Initialize Tuner, Calibrate and Standby\n") % (get_subdev_name()) << std::endl; +    UHD_LOGGER_TRACE("TVRX") << boost::format( +        "\nTVRX2 (%s): Transition 0: Initialize Tuner, Calibrate and Standby\n") % (get_subdev_name()) ;      //Check for Power-On Reset, if reset, initialze tuner      if (get_power_reset()) { @@ -1582,8 +1582,8 @@ void tvrx2::transition_0(void){  void tvrx2::transition_1(void){      //Transition 1: Select TV Standard -    UHD_LOGV(often) << boost::format( -        "\nTVRX2 (%s): Transition 1: Select TV Standard\n") % (get_subdev_name()) << std::endl; +    UHD_LOGGER_TRACE("TVRX") << boost::format( +        "\nTVRX2 (%s): Transition 1: Select TV Standard\n") % (get_subdev_name()) ;      //send magic xtal_cal_dac setting      send_reg(0x65, 0x65); @@ -1613,8 +1613,8 @@ void tvrx2::transition_1(void){  void tvrx2::transition_2(int rf_freq){      //Transition 2: Select RF Frequency after changing TV Standard -    UHD_LOGV(often) << boost::format( -        "\nTVRX2 (%s): Transition 2: Select RF Frequency after changing TV Standard\n") % (get_subdev_name()) << std::endl; +    UHD_LOGGER_TRACE("TVRX") << boost::format( +        "\nTVRX2 (%s): Transition 2: Select RF Frequency after changing TV Standard\n") % (get_subdev_name()) ;      //send magic xtal_cal_dac setting      send_reg(0x65, 0x65); @@ -1651,8 +1651,8 @@ void tvrx2::transition_2(int rf_freq){  void tvrx2::transition_3(void){      //Transition 3: Standby Mode -    UHD_LOGV(often) << boost::format( -        "\nTVRX2 (%s): Transition 3: Standby Mode\n") % (get_subdev_name()) << std::endl; +    UHD_LOGGER_TRACE("TVRX") << boost::format( +        "\nTVRX2 (%s): Transition 3: Standby Mode\n") % (get_subdev_name()) ;      //send magic xtal_cal_dac setting      send_reg(0x65, 0x65); @@ -1670,8 +1670,8 @@ void tvrx2::transition_3(void){  void tvrx2::transition_4(int rf_freq){      //Transition 4: Change RF Frequency without changing TV Standard -    UHD_LOGV(often) << boost::format( -        "\nTVRX2 (%s): Transition 4: Change RF Frequency without changing TV Standard\n") % (get_subdev_name()) << std::endl; +    UHD_LOGGER_TRACE("TVRX") << boost::format( +        "\nTVRX2 (%s): Transition 4: Change RF Frequency without changing TV Standard\n") % (get_subdev_name()) ;      //send magic xtal_cal_dac setting      send_reg(0x65, 0x65); @@ -1699,8 +1699,8 @@ void tvrx2::wait_irq(void){      int timeout = 20; //irq waiting timeout in milliseconds      //int irq = (this->get_iface()->read_gpio(dboard_iface::UNIT_RX) & int(tvrx2_sd_name_to_irq_io[get_subdev_name()]));      bool irq = get_irq(); -    UHD_LOGV(often) << boost::format( -        "\nTVRX2 (%s): Waiting on IRQ, subdev = %d, mask = 0x%x, Status: 0x%x\n") % (get_subdev_name()) % get_subdev_name() % (int(tvrx2_sd_name_to_irq_io[get_subdev_name()])) % irq << std::endl; +    UHD_LOGGER_TRACE("TVRX") << boost::format( +        "\nTVRX2 (%s): Waiting on IRQ, subdev = %d, mask = 0x%x, Status: 0x%x\n") % (get_subdev_name()) % get_subdev_name() % (int(tvrx2_sd_name_to_irq_io[get_subdev_name()])) % irq ;      while (not irq and timeout > 0) {          //irq = (this->get_iface()->read_gpio(dboard_iface::UNIT_RX) & tvrx2_sd_name_to_irq_io[get_subdev_name()]); @@ -1709,13 +1709,13 @@ void tvrx2::wait_irq(void){          timeout -= 1;      } -    UHD_LOGV(often) << boost::format( -        "\nTVRX2 (%s): IRQ Raised, subdev = %d, mask = 0x%x, Status: 0x%x, Timeout: %d\n") % (get_subdev_name()) % get_subdev_name() % (int(tvrx2_sd_name_to_irq_io[get_subdev_name()])) % irq % timeout << std::endl; +    UHD_LOGGER_TRACE("TVRX") << boost::format( +        "\nTVRX2 (%s): IRQ Raised, subdev = %d, mask = 0x%x, Status: 0x%x, Timeout: %d\n") % (get_subdev_name()) % get_subdev_name() % (int(tvrx2_sd_name_to_irq_io[get_subdev_name()])) % irq % timeout ;      read_reg(0xA, 0xB);      //UHD_ASSERT_THROW(timeout > 0); -    if(timeout <= 0) UHD_MSG(warning) << boost::format( -        "\nTVRX2 (%s): Timeout waiting on IRQ\n") % (get_subdev_name()) << std::endl; +    if(timeout <= 0) UHD_LOGGER_WARNING("TVRX") << boost::format( +        "\nTVRX2 (%s): Timeout waiting on IRQ\n") % (get_subdev_name()) ;      _tda18272hnm_regs.irq_clear = tda18272hnm_regs_t::IRQ_CLEAR_TRUE;      send_reg(0xA, 0xA); @@ -1723,8 +1723,8 @@ void tvrx2::wait_irq(void){      irq = (this->get_iface()->read_gpio(dboard_iface::UNIT_RX) & tvrx2_sd_name_to_irq_io[get_subdev_name()]) > 0; -    UHD_LOGV(often) << boost::format( -        "\nTVRX2 (%s): Cleared IRQ, subdev = %d, mask = 0x%x, Status: 0x%x\n") % (get_subdev_name()) % get_subdev_name() % (int(tvrx2_sd_name_to_irq_io[get_subdev_name()])) % irq << std::endl; +    UHD_LOGGER_TRACE("TVRX") << boost::format( +        "\nTVRX2 (%s): Cleared IRQ, subdev = %d, mask = 0x%x, Status: 0x%x\n") % (get_subdev_name()) % get_subdev_name() % (int(tvrx2_sd_name_to_irq_io[get_subdev_name()])) % irq ;  } @@ -1748,20 +1748,20 @@ double tvrx2::set_lo_freq(double target_freq){      _lo_freq = get_scaled_rf_freq() + get_scaled_if_freq(); // - _bandwidth/2;      //debug output of calculated variables -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("TVRX") << boost::format(          "\nTVRX2 (%s): LO Frequency\n"          "\tRequested: \t%f\n"          "\tComputed: \t%f\n"          "\tReadback: \t%f\n" -        "\tIF Frequency: \t%f\n") % (get_subdev_name()) % target_freq % double(int(target_freq/1e3)*1e3) % get_scaled_rf_freq() % get_scaled_if_freq() << std::endl; +        "\tIF Frequency: \t%f\n") % (get_subdev_name()) % target_freq % double(int(target_freq/1e3)*1e3) % get_scaled_rf_freq() % get_scaled_if_freq() ;      get_locked();      test_rf_filter_robustness(); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("TVRX") << boost::format(          "\nTVRX2 (%s): RSSI = %f dBm\n" -    ) % (get_subdev_name()) % (get_rssi().to_real()) << std::endl; +    ) % (get_subdev_name()) % (get_rssi().to_real()) ;      return _lo_freq;  } @@ -1783,9 +1783,9 @@ static double gain_to_if_gain_dac(double &gain){      //calculate the voltage for the aux dac      double dac_volts = gain*slope + min_volts; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("TVRX") << boost::format(          "TVRX2 IF Gain: %f dB, dac_volts: %f V" -    ) % gain % dac_volts << std::endl; +    ) % gain % dac_volts ;      //the actual gain setting      gain = (dac_volts - min_volts)/slope; @@ -1847,9 +1847,9 @@ double tvrx2::set_bandwidth(double bandwidth){      //update register      send_reg(0x13, 0x13); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("TVRX") << boost::format(          "TVRX2 (%s) Bandwidth (lp_fc): %f Hz, reg: %d" -    ) % (get_subdev_name()) % _bandwidth % (int(_tda18272hnm_regs.lp_fc)) << std::endl; +    ) % (get_subdev_name()) % _bandwidth % (int(_tda18272hnm_regs.lp_fc)) ;      return _bandwidth;  } diff --git a/host/lib/usrp/dboard/db_twinrx.cpp b/host/lib/usrp/dboard/db_twinrx.cpp index 2af6bc4ff..91b38f90c 100644 --- a/host/lib/usrp/dboard/db_twinrx.cpp +++ b/host/lib/usrp/dboard/db_twinrx.cpp @@ -265,7 +265,7 @@ public:          // Add workers to expert          //---------------------------------------------------------          //Channel (front-end) specific -        BOOST_FOREACH(const std::string& fe, _fe_names) { +        for(const std::string& fe:  _fe_names) {              expert_factory::add_worker_node<twinrx_freq_path_expert>(_expert, _expert->node_retriever(), fe);              expert_factory::add_worker_node<twinrx_freq_coercion_expert>(_expert, _expert->node_retriever(), fe);              expert_factory::add_worker_node<twinrx_chan_gain_expert>(_expert, _expert->node_retriever(), fe); diff --git a/host/lib/usrp/dboard/db_ubx.cpp b/host/lib/usrp/dboard/db_ubx.cpp index 3dd0b1c84..d25aabe98 100644 --- a/host/lib/usrp/dboard/db_ubx.cpp +++ b/host/lib/usrp/dboard/db_ubx.cpp @@ -27,7 +27,7 @@  #include <uhd/usrp/dboard_manager.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/utils/static.hpp>  #include <uhd/utils/safe_call.hpp>  #include <boost/assign/list_of.hpp> @@ -300,7 +300,7 @@ public:              {                  std::vector<double> rates = _iface->get_clock_rates(dboard_iface::UNIT_RX);                  double highest_rate = 0.0; -                BOOST_FOREACH(double rate, rates) +                for(double rate:  rates)                  {                      if (rate <= pfd_freq_max and rate > highest_rate)                          highest_rate = rate; @@ -312,7 +312,7 @@ public:              {                  std::vector<double> rates = _iface->get_clock_rates(dboard_iface::UNIT_TX);                  double highest_rate = 0.0; -                BOOST_FOREACH(double rate, rates) +                for(double rate:  rates)                  {                      if (rate <= pfd_freq_max and rate > highest_rate)                          highest_rate = rate; @@ -370,7 +370,7 @@ public:              _rxlo1 = max287x_iface::make<max2870>(boost::bind(&ubx_xcvr::write_spi_regs, this, RXLO1, _1));              _rxlo2 = max287x_iface::make<max2870>(boost::bind(&ubx_xcvr::write_spi_regs, this, RXLO2, _1));              std::vector<max287x_iface::sptr> los = boost::assign::list_of(_txlo1)(_txlo2)(_rxlo1)(_rxlo2); -            BOOST_FOREACH(max287x_iface::sptr lo, los) +            for(max287x_iface::sptr lo:  los)              {                  lo->set_auto_retune(false);                  lo->set_muxout_mode(max287x_iface::MUXOUT_DLD); @@ -384,7 +384,7 @@ public:              _rxlo1 = max287x_iface::make<max2871>(boost::bind(&ubx_xcvr::write_spi_regs, this, RXLO1, _1));              _rxlo2 = max287x_iface::make<max2871>(boost::bind(&ubx_xcvr::write_spi_regs, this, RXLO2, _1));              std::vector<max287x_iface::sptr> los = boost::assign::list_of(_txlo1)(_txlo2)(_rxlo1)(_rxlo2); -            BOOST_FOREACH(max287x_iface::sptr lo, los) +            for(max287x_iface::sptr lo:  los)              {                  lo->set_auto_retune(false);                  //lo->set_cycle_slip_mode(true);  // tried it - caused longer lock times @@ -547,7 +547,7 @@ private:      {          boost::mutex::scoped_lock lock(_spi_mutex);          ROUTE_SPI(_iface, dest); -        BOOST_FOREACH(uint32_t value, values) +        for(uint32_t value:  values)              WRITE_SPI(_iface, value);      } @@ -749,7 +749,7 @@ private:          _ubx_tx_atten_val = ((attn_code & 0x3F) << 10);          set_gpio_field(TX_GAIN, attn_code);          write_gpio(); -        UHD_LOGV(rarely) << boost::format("UBX TX Gain: %f dB, Code: %d, IO Bits 0x%04x") % gain % attn_code % _ubx_tx_atten_val << std::endl; +        UHD_LOGGER_TRACE("UBX") << boost::format("UBX TX Gain: %f dB, Code: %d, IO Bits 0x%04x") % gain % attn_code % _ubx_tx_atten_val ;          _tx_gain = gain;          return gain;      } @@ -762,7 +762,7 @@ private:          _ubx_rx_atten_val = ((attn_code & 0x3F) << 10);          set_gpio_field(RX_GAIN, attn_code);          write_gpio(); -        UHD_LOGV(rarely) << boost::format("UBX RX Gain: %f dB, Code: %d, IO Bits 0x%04x") % gain % attn_code % _ubx_rx_atten_val << std::endl; +        UHD_LOGGER_TRACE("UBX") << boost::format("UBX RX Gain: %f dB, Code: %d, IO Bits 0x%04x") % gain % attn_code % _ubx_rx_atten_val ;          _rx_gain = gain;          return gain;      } @@ -786,18 +786,18 @@ private:          property_tree::sptr subtree = this->get_tx_subtree();          device_addr_t tune_args = subtree->access<device_addr_t>("tune_args").get();          is_int_n = boost::iequals(tune_args.get("mode_n",""), "integer"); -        UHD_LOGV(rarely) << boost::format("UBX TX: the requested frequency is %f MHz") % (freq/1e6) << std::endl; +        UHD_LOGGER_TRACE("UBX") << boost::format("UBX TX: the requested frequency is %f MHz") % (freq/1e6) ;          double target_pfd_freq = _tx_target_pfd_freq;          if (is_int_n and tune_args.has_key("int_n_step"))          {              target_pfd_freq = tune_args.cast<double>("int_n_step", _tx_target_pfd_freq);              if (target_pfd_freq > _tx_target_pfd_freq)              { -                UHD_MSG(warning) +                UHD_LOGGER_WARNING("UBX")                      << boost::format("Requested int_n_step of %f MHz too large, clipping to %f MHz")                      % (target_pfd_freq/1e6)                      % (_tx_target_pfd_freq/1e6) -                    << std::endl; +                    ;                  target_pfd_freq = _tx_target_pfd_freq;              }          } @@ -925,7 +925,7 @@ private:          _txlo1_freq = freq_lo1;          _txlo2_freq = freq_lo2; -        UHD_LOGV(rarely) << boost::format("UBX TX: the actual frequency is %f MHz") % (_tx_freq/1e6) << std::endl; +        UHD_LOGGER_TRACE("UBX") << boost::format("UBX TX: the actual frequency is %f MHz") % (_tx_freq/1e6) ;          return _tx_freq;      } @@ -938,7 +938,7 @@ private:          double ref_freq = _iface->get_clock_rate(dboard_iface::UNIT_RX);          bool is_int_n = false; -        UHD_LOGV(rarely) << boost::format("UBX RX: the requested frequency is %f MHz") % (freq/1e6) << std::endl; +        UHD_LOGGER_TRACE("UBX") << boost::format("UBX RX: the requested frequency is %f MHz") % (freq/1e6) ;          property_tree::sptr subtree = this->get_rx_subtree();          device_addr_t tune_args = subtree->access<device_addr_t>("tune_args").get(); @@ -949,11 +949,11 @@ private:              target_pfd_freq = tune_args.cast<double>("int_n_step", _rx_target_pfd_freq);              if (target_pfd_freq > _rx_target_pfd_freq)              { -                UHD_MSG(warning) +                UHD_LOGGER_WARNING("UBX")                      << boost::format("Requested int_n_step of %f Mhz too large, clipping to %f MHz")                      % (target_pfd_freq/1e6)                      % (_rx_target_pfd_freq/1e6) -                    << std::endl; +                    ;                  target_pfd_freq = _rx_target_pfd_freq;              }          } @@ -1121,7 +1121,7 @@ private:          _rxlo1_freq = freq_lo1;          _rxlo2_freq = freq_lo2; -        UHD_LOGV(rarely) << boost::format("UBX RX: the actual frequency is %f MHz") % (_rx_freq/1e6) << std::endl; +        UHD_LOGGER_TRACE("UBX") << boost::format("UBX RX: the actual frequency is %f MHz") % (_rx_freq/1e6) ;          return _rx_freq;      } diff --git a/host/lib/usrp/dboard/db_unknown.cpp b/host/lib/usrp/dboard/db_unknown.cpp index 2ed50cd91..1a63c9233 100644 --- a/host/lib/usrp/dboard/db_unknown.cpp +++ b/host/lib/usrp/dboard/db_unknown.cpp @@ -18,12 +18,11 @@  #include <uhd/types/ranges.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/static.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/usrp/dboard_base.hpp>  #include <uhd/usrp/dboard_manager.hpp>  #include <boost/assign/list_of.hpp>  #include <boost/format.hpp> -#include <boost/foreach.hpp>  #include <boost/tuple/tuple.hpp>  #include <vector> @@ -43,13 +42,13 @@ static void warn_if_old_rfx(const dboard_id_t &dboard_id, const std::string &xx)          (old_ids_t("Flex 1800 Classic", 0x0030, 0x0031))          (old_ids_t("Flex 2400 Classic", 0x0007, 0x000b))      ; -    BOOST_FOREACH(const old_ids_t &old_id, old_rfx_ids){ +    for(const old_ids_t &old_id:  old_rfx_ids){          std::string name; dboard_id_t rx_id, tx_id;          boost::tie(name, rx_id, tx_id) = old_id;          if (              (xx == "RX" and rx_id == dboard_id) or              (xx == "TX" and tx_id == dboard_id) -        ) UHD_MSG(warning) << boost::format( +        ) UHD_LOGGER_WARNING("unknown_db") << boost::format(              "Detected %s daughterboard %s\n"              "This board requires modification to use.\n"              "See the daughterboard application notes.\n" diff --git a/host/lib/usrp/dboard/db_wbx_common.cpp b/host/lib/usrp/dboard/db_wbx_common.cpp index 5afbb1f88..1f665b7e4 100644 --- a/host/lib/usrp/dboard/db_wbx_common.cpp +++ b/host/lib/usrp/dboard/db_wbx_common.cpp @@ -21,7 +21,7 @@  #include <uhd/types/sensors.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/algorithm.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  using namespace uhd;  using namespace uhd::usrp; @@ -42,9 +42,9 @@ static int rx_pga0_gain_to_iobits(double &gain){      int attn_code = boost::math::iround(attn*2);      int iobits = ((~attn_code) << RX_ATTN_SHIFT) & RX_ATTN_MASK; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("WBX") << boost::format(          "WBX RX Attenuation: %f dB, Code: %d, IO Bits %x, Mask: %x" -    ) % attn % attn_code % (iobits & RX_ATTN_MASK) % RX_ATTN_MASK << std::endl; +    ) % attn % attn_code % (iobits & RX_ATTN_MASK) % RX_ATTN_MASK ;      //the actual gain setting      gain = wbx_rx_gain_ranges["PGA0"].stop() - double(attn_code)/2; @@ -70,7 +70,7 @@ wbx_base::wbx_base(ctor_args_t args) : xcvr_dboard_base(args){      this->get_rx_subtree()->create<device_addr_t>("tune_args").set(device_addr_t());      this->get_rx_subtree()->create<sensor_value_t>("sensors/lo_locked")          .set_publisher(boost::bind(&wbx_base::get_locked, this, dboard_iface::UNIT_RX)); -    BOOST_FOREACH(const std::string &name, wbx_rx_gain_ranges.keys()){ +    for(const std::string &name:  wbx_rx_gain_ranges.keys()){          this->get_rx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&wbx_base::set_rx_gain, this, _1, name))              .set(wbx_rx_gain_ranges[name].start()); @@ -158,7 +158,7 @@ sensor_value_t wbx_base::get_locked(dboard_iface::unit_t unit){  }  void wbx_base::wbx_versionx::write_lo_regs(dboard_iface::unit_t unit, const std::vector<uint32_t> ®s) { -    BOOST_FOREACH(uint32_t reg, regs) { +    for(uint32_t reg:  regs) {          self_base->get_iface()->write_spi(unit, spi_config_t::EDGE_RISE, reg, 32);      }  } diff --git a/host/lib/usrp/dboard/db_wbx_version2.cpp b/host/lib/usrp/dboard/db_wbx_version2.cpp index 489291881..d50ae481b 100644 --- a/host/lib/usrp/dboard/db_wbx_version2.cpp +++ b/host/lib/usrp/dboard/db_wbx_version2.cpp @@ -23,7 +23,7 @@  #include <uhd/types/sensors.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/algorithm.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/usrp/dboard_base.hpp>  #include <boost/assign/list_of.hpp>  #include <boost/format.hpp> @@ -58,9 +58,9 @@ static double tx_pga0_gain_to_dac_volts(double &gain){      //calculate the voltage for the aux dac      double dac_volts = gain*slope + min_volts; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("WBX") << boost::format(          "WBX TX Gain: %f dB, dac_volts: %f V" -    ) % gain % dac_volts << std::endl; +    ) % gain % dac_volts ;      //the actual gain setting      gain = (dac_volts - min_volts)/slope; @@ -91,7 +91,7 @@ wbx_base::wbx_version2::wbx_version2(wbx_base *_self_wbx_base) {      // Register TX properties      ////////////////////////////////////////////////////////////////////      this->get_tx_subtree()->create<std::string>("name").set("WBXv2 TX"); -    BOOST_FOREACH(const std::string &name, wbx_v2_tx_gain_ranges.keys()){ +    for(const std::string &name:  wbx_v2_tx_gain_ranges.keys()){          self_base->get_tx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&wbx_base::wbx_version2::set_tx_gain, this, _1, name))              .set(wbx_v2_tx_gain_ranges[name].start()); @@ -165,9 +165,9 @@ double wbx_base::wbx_version2::set_lo_freq(dboard_iface::unit_t unit, double tar      //clip to tuning range      target_freq = wbx_v2_freq_range.clip(target_freq); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("WBX") << boost::format(          "WBX tune: target frequency %f MHz" -    ) % (target_freq/1e6) << std::endl; +    ) % (target_freq/1e6) ;      /*       * If the user sets 'mode_n=integer' in the tuning args, the user wishes to diff --git a/host/lib/usrp/dboard/db_wbx_version3.cpp b/host/lib/usrp/dboard/db_wbx_version3.cpp index 1bd326e6f..1863dcb44 100644 --- a/host/lib/usrp/dboard/db_wbx_version3.cpp +++ b/host/lib/usrp/dboard/db_wbx_version3.cpp @@ -22,7 +22,7 @@  #include <uhd/types/sensors.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/algorithm.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/usrp/dboard_base.hpp>  #include <boost/assign/list_of.hpp>  #include <boost/format.hpp> @@ -63,9 +63,9 @@ static int tx_pga0_gain_to_iobits(double &gain){              (attn_code &  1 ? 0 : TX_ATTN_1)          ) & TX_ATTN_MASK; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("WBX") << boost::format(          "WBX TX Attenuation: %f dB, Code: %d, IO Bits %x, Mask: %x" -    ) % attn % attn_code % (iobits & TX_ATTN_MASK) % TX_ATTN_MASK << std::endl; +    ) % attn % attn_code % (iobits & TX_ATTN_MASK) % TX_ATTN_MASK ;      //the actual gain setting      gain = wbx_v3_tx_gain_ranges["PGA0"].stop() - double(attn_code); @@ -96,7 +96,7 @@ wbx_base::wbx_version3::wbx_version3(wbx_base *_self_wbx_base) {      // Register TX properties      ////////////////////////////////////////////////////////////////////      this->get_tx_subtree()->create<std::string>("name").set("WBXv3 TX"); -    BOOST_FOREACH(const std::string &name, wbx_v3_tx_gain_ranges.keys()){ +    for(const std::string &name:  wbx_v3_tx_gain_ranges.keys()){          self_base->get_tx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&wbx_base::wbx_version3::set_tx_gain, this, _1, name))              .set(wbx_v3_tx_gain_ranges[name].start()); @@ -196,9 +196,9 @@ double wbx_base::wbx_version3::set_lo_freq(dboard_iface::unit_t unit, double tar      //clip to tuning range      target_freq = wbx_v3_freq_range.clip(target_freq); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("WBX") << boost::format(          "WBX tune: target frequency %f MHz" -    ) % (target_freq/1e6) << std::endl; +    ) % (target_freq/1e6) ;      /*       * If the user sets 'mode_n=integer' in the tuning args, the user wishes to diff --git a/host/lib/usrp/dboard/db_wbx_version4.cpp b/host/lib/usrp/dboard/db_wbx_version4.cpp index 3cc0f1887..9b31baf89 100644 --- a/host/lib/usrp/dboard/db_wbx_version4.cpp +++ b/host/lib/usrp/dboard/db_wbx_version4.cpp @@ -22,7 +22,7 @@  #include <uhd/types/sensors.hpp>  #include <uhd/utils/assert_has.hpp>  #include <uhd/utils/algorithm.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/usrp/dboard_base.hpp>  #include <boost/assign/list_of.hpp>  #include <boost/format.hpp> @@ -64,9 +64,9 @@ static int tx_pga0_gain_to_iobits(double &gain){              (attn_code &  1 ? 0 : TX_ATTN_1)          ) & TX_ATTN_MASK; -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("WBX") << boost::format(          "WBX TX Attenuation: %f dB, Code: %d, IO Bits %x, Mask: %x" -    ) % attn % attn_code % (iobits & TX_ATTN_MASK) % TX_ATTN_MASK << std::endl; +    ) % attn % attn_code % (iobits & TX_ATTN_MASK) % TX_ATTN_MASK ;      //the actual gain setting      gain = wbx_v4_tx_gain_ranges["PGA0"].stop() - double(attn_code); @@ -103,7 +103,7 @@ wbx_base::wbx_version4::wbx_version4(wbx_base *_self_wbx_base) {      //get_tx_id() will always return GDB ID, so use RX ID to determine WBXv4 vs. WBX-120      if(rx_id == 0x0063) this->get_tx_subtree()->create<std::string>("name").set("WBXv4 TX");      else if(rx_id == 0x0081) this->get_tx_subtree()->create<std::string>("name").set("WBX-120 TX"); -    BOOST_FOREACH(const std::string &name, wbx_v4_tx_gain_ranges.keys()){ +    for(const std::string &name:  wbx_v4_tx_gain_ranges.keys()){          self_base->get_tx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&wbx_base::wbx_version4::set_tx_gain, this, _1, name))              .set(wbx_v4_tx_gain_ranges[name].start()); @@ -204,9 +204,9 @@ double wbx_base::wbx_version4::set_lo_freq(dboard_iface::unit_t unit, double tar      //clip to tuning range      target_freq = wbx_v4_freq_range.clip(target_freq); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("WBX") << boost::format(          "WBX tune: target frequency %f MHz" -    ) % (target_freq/1e6) << std::endl; +    ) % (target_freq/1e6) ;      /*       * If the user sets 'mode_n=integer' in the tuning args, the user wishes to diff --git a/host/lib/usrp/dboard/db_xcvr2450.cpp b/host/lib/usrp/dboard/db_xcvr2450.cpp index 6876ee4be..62c5c39fb 100644 --- a/host/lib/usrp/dboard/db_xcvr2450.cpp +++ b/host/lib/usrp/dboard/db_xcvr2450.cpp @@ -135,9 +135,9 @@ private:      void spi_reset(void);      void send_reg(uint8_t addr){          uint32_t value = _max2829_regs.get_reg(addr); -        UHD_LOGV(often) << boost::format( +        UHD_LOGGER_TRACE("XCVR2450") << boost::format(              "XCVR2450: send reg 0x%02x, value 0x%05x" -        ) % int(addr) % value << std::endl; +        ) % int(addr) % value ;          this->get_iface()->write_spi(              dboard_iface::UNIT_RX,              spi_config_t::EDGE_RISE, @@ -234,7 +234,7 @@ xcvr2450::xcvr2450(ctor_args_t args) : xcvr_dboard_base(args){          .set_publisher(boost::bind(&xcvr2450::get_locked, this));      this->get_rx_subtree()->create<sensor_value_t>("sensors/rssi")          .set_publisher(boost::bind(&xcvr2450::get_rssi, this)); -    BOOST_FOREACH(const std::string &name, xcvr_rx_gain_ranges.keys()){ +    for(const std::string &name:  xcvr_rx_gain_ranges.keys()){          this->get_rx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&xcvr2450::set_rx_gain, this, _1, name))              .set(xcvr_rx_gain_ranges[name].start()); @@ -270,7 +270,7 @@ xcvr2450::xcvr2450(ctor_args_t args) : xcvr_dboard_base(args){          .set("XCVR2450 TX");      this->get_tx_subtree()->create<sensor_value_t>("sensors/lo_locked")          .set_publisher(boost::bind(&xcvr2450::get_locked, this)); -    BOOST_FOREACH(const std::string &name, xcvr_tx_gain_ranges.keys()){ +    for(const std::string &name:  xcvr_tx_gain_ranges.keys()){          this->get_tx_subtree()->create<double>("gains/"+name+"/value")              .set_coercer(boost::bind(&xcvr2450::set_tx_gain, this, _1, name))              .set(xcvr_tx_gain_ranges[name].start()); @@ -391,20 +391,20 @@ double xcvr2450::set_lo_freq_core(double target_freq){      double N = double(intdiv) + double(fracdiv)/double(1 << 16);      _lo_freq = (N*ref_freq)/(scaler*R*_ad9515div); -    UHD_LOGV(often) +    UHD_LOGGER_TRACE("XCVR2450")          << boost::format("XCVR2450 tune:\n")          << boost::format("    R=%d, N=%f, ad9515=%d, scaler=%f\n") % R % N % _ad9515div % scaler          << boost::format("    Ref    Freq=%fMHz\n") % (ref_freq/1e6)          << boost::format("    Target Freq=%fMHz\n") % (target_freq/1e6)          << boost::format("    Actual Freq=%fMHz\n") % (_lo_freq/1e6) -        << std::endl; +        ;      //high-high band or low-high band?      if(_lo_freq > (5.35e9 + 5.47e9)/2.0){ -        UHD_LOGV(often) << "XCVR2450 tune: Using  high-high band" << std::endl; +        UHD_LOGGER_TRACE("XCVR2450") << "XCVR2450 tune: Using  high-high band" ;          _max2829_regs.band_select_802_11a = max2829_regs_t::BAND_SELECT_802_11A_5_47GHZ_TO_5_875GHZ;      }else{ -        UHD_LOGV(often) << "XCVR2450 tune: Using  low-high band" << std::endl; +        UHD_LOGGER_TRACE("XCVR2450") << "XCVR2450 tune: Using  low-high band" ;          _max2829_regs.band_select_802_11a = max2829_regs_t::BAND_SELECT_802_11A_4_9GHZ_TO_5_35GHZ;      } @@ -655,9 +655,9 @@ double xcvr2450::set_rx_bandwidth(double bandwidth){      //update register      send_reg(0x7); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("XCVR2450") << boost::format(          "XCVR2450 RX Bandwidth (lp_fc): %f Hz, coarse reg: %d, fine reg: %d" -    ) % _rx_bandwidth % (int(_max2829_regs.rx_lpf_coarse_adj)) % (int(_max2829_regs.rx_lpf_fine_adj)) << std::endl; +    ) % _rx_bandwidth % (int(_max2829_regs.rx_lpf_coarse_adj)) % (int(_max2829_regs.rx_lpf_fine_adj)) ;      return 2.0*_rx_bandwidth;  } @@ -675,9 +675,9 @@ double xcvr2450::set_tx_bandwidth(double bandwidth){      //update register      send_reg(0x7); -    UHD_LOGV(often) << boost::format( +    UHD_LOGGER_TRACE("XCVR2450") << boost::format(          "XCVR2450 TX Bandwidth (lp_fc): %f Hz, coarse reg: %d" -    ) % _tx_bandwidth % (int(_max2829_regs.tx_lpf_coarse_adj)) << std::endl; +    ) % _tx_bandwidth % (int(_max2829_regs.tx_lpf_coarse_adj)) ;      //convert lowpass back to complex bandpass bandwidth      return 2.0*_tx_bandwidth; diff --git a/host/lib/usrp/dboard/twinrx/twinrx_ctrl.cpp b/host/lib/usrp/dboard/twinrx/twinrx_ctrl.cpp index 346f39589..ddbbfaefb 100644 --- a/host/lib/usrp/dboard/twinrx/twinrx_ctrl.cpp +++ b/host/lib/usrp/dboard/twinrx/twinrx_ctrl.cpp @@ -87,10 +87,10 @@ public:          //Initialize clocks and LO          bool found_rate = false; -        BOOST_FOREACH(double rate, _db_iface->get_clock_rates(dboard_iface::UNIT_TX)) { +        for(double rate:  _db_iface->get_clock_rates(dboard_iface::UNIT_TX)) {              found_rate |= uhd::math::frequencies_are_equal(rate, TWINRX_DESIRED_REFERENCE_FREQ);          } -        BOOST_FOREACH(double rate, _db_iface->get_clock_rates(dboard_iface::UNIT_RX)) { +        for(double rate:  _db_iface->get_clock_rates(dboard_iface::UNIT_RX)) {              found_rate |= uhd::math::frequencies_are_equal(rate, TWINRX_DESIRED_REFERENCE_FREQ);          }          if (not found_rate) { @@ -506,7 +506,7 @@ private:    //Functions      void _write_lo_spi(dboard_iface::unit_t unit, const std::vector<uint32_t> ®s)      { -        BOOST_FOREACH(uint32_t reg, regs) { +        for(uint32_t reg:  regs) {               spi_config_t spi_config = spi_config_t(spi_config_t::EDGE_RISE);               spi_config.use_custom_divider = true;               spi_config.divider = 67; diff --git a/host/lib/usrp/dboard/twinrx/twinrx_experts.cpp b/host/lib/usrp/dboard/twinrx/twinrx_experts.cpp index 3b41972da..1a66e8fe7 100644 --- a/host/lib/usrp/dboard/twinrx/twinrx_experts.cpp +++ b/host/lib/usrp/dboard/twinrx/twinrx_experts.cpp @@ -18,6 +18,7 @@  #include "twinrx_experts.hpp"  #include "twinrx_gain_tables.hpp"  #include <uhd/utils/math.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/exception.hpp>  #include <uhd/types/dict.hpp>  #include <uhd/types/ranges.hpp> @@ -481,7 +482,7 @@ void twinrx_ant_gain_expert::resolve()              (_ch0_preamp2 != _ch1_preamp2) or              (_ch0_lb_preamp_presel != _ch1_lb_preamp_presel))          { -            UHD_MSG(warning) << "incompatible gain settings for antenna sharing. temporarily using Ch0 settings for Ch1."; +            UHD_LOGGER_WARNING("TWINRX") << "incompatible gain settings for antenna sharing. temporarily using Ch0 settings for Ch1.";          }          _ant0_input_atten       = _ch0_input_atten;          _ant0_preamp1           = _ch0_preamp1; @@ -499,7 +500,7 @@ void twinrx_ant_gain_expert::resolve()              (_ch0_preamp2 != _ch1_preamp2) or              (_ch0_lb_preamp_presel != _ch1_lb_preamp_presel))          { -            UHD_MSG(warning) << "incompatible gain settings for antenna sharing. temporarily using Ch0 settings for Ch1."; +            UHD_LOGGER_WARNING("TWINRX") << "incompatible gain settings for antenna sharing. temporarily using Ch0 settings for Ch1.";          }          _ant1_input_atten       = _ch0_input_atten;          _ant1_preamp1           = _ch0_preamp1; diff --git a/host/lib/usrp/dboard_eeprom.cpp b/host/lib/usrp/dboard_eeprom.cpp index 9c748f556..900d28e80 100644 --- a/host/lib/usrp/dboard_eeprom.cpp +++ b/host/lib/usrp/dboard_eeprom.cpp @@ -19,7 +19,6 @@  #include <uhd/usrp/dboard_eeprom.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/log.hpp> -#include <boost/foreach.hpp>  #include <boost/format.hpp>  #include <boost/lexical_cast.hpp>  #include <algorithm> @@ -68,7 +67,7 @@ static uint8_t checksum(const byte_vector_t &bytes){      for (size_t i = 0; i < std::min(bytes.size(), size_t(DB_EEPROM_CHKSUM)); i++){          sum -= int(bytes.at(i));      } -    UHD_LOGV(often) << boost::format("sum: 0x%02x") % sum << std::endl; +    UHD_LOG_DEBUG("DB_EEPROM", boost::format("byte sum: 0x%02x") % sum)      return uint8_t(sum);  } @@ -82,11 +81,8 @@ void dboard_eeprom_t::load(i2c_iface &iface, uint8_t addr){      std::ostringstream ss;      for (size_t i = 0; i < bytes.size(); i++){ -        ss << boost::format( -            "eeprom byte[0x%02x] = 0x%02x") % i % int(bytes.at(i) -        ) << std::endl; +        UHD_LOG_TRACE("DB_EEPROM",boost::format("eeprom byte[0x%02x] = 0x%02x") % i % int(bytes.at(i)))      } -    UHD_LOGV(often) << ss.str() << std::endl;      try{          UHD_ASSERT_THROW(bytes.size() >= DB_EEPROM_CLEN); diff --git a/host/lib/usrp/dboard_manager.cpp b/host/lib/usrp/dboard_manager.cpp index 56cd08fd7..87b0c9f9c 100644 --- a/host/lib/usrp/dboard_manager.cpp +++ b/host/lib/usrp/dboard_manager.cpp @@ -17,7 +17,7 @@  #include "dboard_ctor_args.hpp"  #include <uhd/usrp/dboard_manager.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp>  #include <uhd/utils/static.hpp> @@ -26,7 +26,6 @@  #include <boost/tuple/tuple.hpp>  #include <boost/format.hpp>  #include <boost/bind.hpp> -#include <boost/foreach.hpp>  #include <boost/assign/list_of.hpp>  using namespace uhd; @@ -97,7 +96,7 @@ static void register_dboard_key(      const std::vector<std::string> &subdev_names,      dboard_manager::dboard_ctor_t db_container_ctor  ){ -    UHD_LOGV(always) << "registering: " << name << std::endl; +    // UHD_LOGGER_TRACE("DBMGR") << "registering: " << name;      if (get_id_to_args_map().has_key(dboard_key)){          if (dboard_key.is_xcvr()) throw uhd::key_error(str(boost::format( @@ -156,7 +155,7 @@ void dboard_manager::register_dboard_restricted(  std::string dboard_id_t::to_cname(void) const{      std::string cname; -    BOOST_FOREACH(const dboard_key_t &key, get_id_to_args_map().keys()){ +    for(const dboard_key_t &key:  get_id_to_args_map().keys()){          if (              (not key.is_xcvr() and *this == key.xx_id()) or              (key.is_xcvr() and (*this == key.rx_id() or *this == key.tx_id())) @@ -248,11 +247,11 @@ dboard_manager_impl::dboard_manager_impl(          this->init(rx_dboard_id, tx_dboard_id, subtree, defer_db_init);      }      catch(const std::exception &e){ -        UHD_MSG(error) << boost::format( +        UHD_LOGGER_ERROR("DBMGR") << boost::format(              "The daughterboard manager encountered a recoverable error in init.\n"              "Loading the \"unknown\" daughterboard implementations to continue.\n"              "The daughterboard cannot operate until this error is resolved.\n" -        ) << e.what() << std::endl; +        ) << e.what() ;          //clean up the stuff added by the call above          if (subtree->exists("rx_frontends")) subtree->remove("rx_frontends");          if (subtree->exists("tx_frontends")) subtree->remove("tx_frontends"); @@ -266,7 +265,7 @@ void dboard_manager_impl::init(  ){      //find the dboard key matches for the dboard ids      dboard_key_t rx_dboard_key, tx_dboard_key, xcvr_dboard_key; -    BOOST_FOREACH(const dboard_key_t &key, get_id_to_args_map().keys()){ +    for(const dboard_key_t &key:  get_id_to_args_map().keys()){          if (key.is_xcvr()){              if (rx_dboard_id == key.rx_id() and tx_dboard_id == key.tx_id()) xcvr_dboard_key = key;              if (rx_dboard_id == key.rx_id()) rx_dboard_key = key; //kept to handle warning @@ -280,7 +279,7 @@ void dboard_manager_impl::init(      //warn for invalid dboard id xcvr combinations      if (not xcvr_dboard_key.is_xcvr() and (rx_dboard_key.is_xcvr() or tx_dboard_key.is_xcvr())){ -        UHD_MSG(warning) << boost::format( +        UHD_LOGGER_WARNING("DBMGR") << boost::format(              "Unknown transceiver board ID combination.\n"              "Is your daughter-board mounted properly?\n"              "RX dboard ID: %s\n" @@ -322,7 +321,7 @@ void dboard_manager_impl::init(          db_ctor_args.tx_container = db_ctor_args.rx_container;  //Same TX and RX container          //create the xcvr object for each subdevice -        BOOST_FOREACH(const std::string &subdev, subdevs){ +        for(const std::string &subdev:  subdevs){              db_ctor_args.sd_name = subdev;              db_ctor_args.rx_subtree = subtree->subtree("rx_frontends/" + db_ctor_args.sd_name);              db_ctor_args.tx_subtree = subtree->subtree("tx_frontends/" + db_ctor_args.sd_name); @@ -373,7 +372,7 @@ void dboard_manager_impl::init(          }          //make the rx subdevs -        BOOST_FOREACH(const std::string &subdev, rx_subdevs){ +        for(const std::string &subdev:  rx_subdevs){              db_ctor_args.sd_name = subdev;              db_ctor_args.rx_subtree = subtree->subtree("rx_frontends/" + db_ctor_args.sd_name);              _rx_dboards[subdev] = rx_dboard_ctor(&db_ctor_args); @@ -412,7 +411,7 @@ void dboard_manager_impl::init(          }          //make the tx subdevs -        BOOST_FOREACH(const std::string &subdev, tx_subdevs){ +        for(const std::string &subdev:  tx_subdevs){              db_ctor_args.sd_name = subdev;              db_ctor_args.tx_subtree = subtree->subtree("tx_frontends/" + db_ctor_args.sd_name);              _tx_dboards[subdev] = tx_dboard_ctor(&db_ctor_args); @@ -436,11 +435,11 @@ void dboard_manager_impl::init(  }  void dboard_manager_impl::initialize_dboards(void) { -    BOOST_FOREACH(dboard_base::sptr& _rx_container, _rx_containers) { +    for(dboard_base::sptr& _rx_container:  _rx_containers) {          _rx_container->initialize();      } -    BOOST_FOREACH(dboard_base::sptr& _tx_container, _tx_containers) { +    for(dboard_base::sptr& _tx_container:  _tx_containers) {          _tx_container->initialize();      }  } @@ -457,7 +456,7 @@ void dboard_manager_impl::set_nice_dboard_if(void){      ;      //set nice settings on each unit -    BOOST_FOREACH(dboard_iface::unit_t unit, units){ +    for(dboard_iface::unit_t unit:  units){          _iface->set_gpio_ddr(unit, 0x0000); //all inputs          _iface->set_gpio_out(unit, 0x0000); //all low          _iface->set_pin_ctrl(unit, 0x0000); //all gpio diff --git a/host/lib/usrp/device3/device3_impl.cpp b/host/lib/usrp/device3/device3_impl.cpp index 50598a519..35faf601f 100644 --- a/host/lib/usrp/device3/device3_impl.cpp +++ b/host/lib/usrp/device3/device3_impl.cpp @@ -18,17 +18,16 @@  #include "device3_impl.hpp"  #include "graph_impl.hpp"  #include "ctrl_iface.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/rfnoc/block_ctrl_base.hpp>  #include <boost/make_shared.hpp>  #include <algorithm> -#define UHD_DEVICE3_LOG() UHD_LOGV(never) +#define UHD_DEVICE3_LOG() UHD_LOGGER_TRACE("DEVICE3")  using namespace uhd::usrp;  device3_impl::device3_impl() -    : _sid_framer(0)  {      _type = uhd::device::USRP;      _async_md.reset(new async_md_type(1000/*messages deep*/)); @@ -70,7 +69,7 @@ void device3_impl::merge_channel_defs(      //    - All block indices that are in chan_ids may be overwritten in the channel definition      //    - If the channels in chan_ids are not yet in the property tree channel list,      //      they are appended. -    BOOST_FOREACH(const std::string &chan_idx, curr_channels) { +    for(const std::string &chan_idx:  curr_channels) {          if (_tree->exists(chans_root / chan_idx)) {              rfnoc::block_id_t chan_block_id = _tree->access<rfnoc::block_id_t>(chans_root / chan_idx).get();              if (std::find(chan_ids.begin(), chan_ids.end(), chan_block_id) != chan_ids.end()) { @@ -105,8 +104,7 @@ void device3_impl::enumerate_rfnoc_blocks(          size_t n_blocks,          size_t base_port,          const uhd::sid_t &base_sid, -        uhd::device_addr_t transport_args, -        uhd::endianness_t endianness +        uhd::device_addr_t transport_args  ) {      // entries that are already connected to this block      uhd::sid_t ctrl_sid = base_sid; @@ -120,7 +118,7 @@ void device3_impl::enumerate_rfnoc_blocks(      // TODO: Clear out all the old block control classes      // 3) Create new block controllers      for (size_t i = 0; i < n_blocks; i++) { -        UHD_DEVICE3_LOG() << "[RFNOC] ------- Block Setup -----------" << std::endl; +        UHD_DEVICE3_LOG() << "[RFNOC] ------- Block Setup -----------" ;          // First, make a transport for port number zero, because we always need that:          ctrl_sid.set_dst_xbarport(base_port + i);          ctrl_sid.set_dst_blockport(0); @@ -131,24 +129,24 @@ void device3_impl::enumerate_rfnoc_blocks(          );          UHD_DEVICE3_LOG() << str(boost::format("Setting up NoC-Shell Control for port #0 (SID: %s)...") % xport.send_sid.to_pp_string_hex());          uhd::rfnoc::ctrl_iface::sptr ctrl = uhd::rfnoc::ctrl_iface::make( -                endianness == ENDIANNESS_BIG, +                xport.endianness == uhd::ENDIANNESS_BIG,                  xport.send,                  xport.recv,                  xport.send_sid,                  str(boost::format("CE_%02d_Port_%02X") % i % ctrl_sid.get_dst_endpoint())          ); -        UHD_DEVICE3_LOG() << "OK" << std::endl; +        UHD_DEVICE3_LOG() << "OK" ;          uint64_t noc_id = ctrl->peek64(uhd::rfnoc::SR_READBACK_REG_ID); -        UHD_DEVICE3_LOG() << str(boost::format("Port %d: Found NoC-Block with ID %016X.") % int(ctrl_sid.get_dst_endpoint()) % noc_id) << std::endl; +        UHD_DEVICE3_LOG() << str(boost::format("Port %d: Found NoC-Block with ID %016X.") % int(ctrl_sid.get_dst_endpoint()) % noc_id) ;          uhd::rfnoc::make_args_t make_args;          uhd::rfnoc::blockdef::sptr block_def = uhd::rfnoc::blockdef::make_from_noc_id(noc_id);          if (not block_def) { -            UHD_DEVICE3_LOG() << "Using default block configuration." << std::endl; +            UHD_DEVICE3_LOG() << "Using default block configuration." ;              block_def = uhd::rfnoc::blockdef::make_from_noc_id(uhd::rfnoc::DEFAULT_NOC_ID);          }          UHD_ASSERT_THROW(block_def);          make_args.ctrl_ifaces[0] = ctrl; -        BOOST_FOREACH(const size_t port_number, block_def->get_all_port_numbers()) { +        for(const size_t port_number:  block_def->get_all_port_numbers()) {              if (port_number == 0) { // We've already set this up                  continue;              } @@ -160,21 +158,23 @@ void device3_impl::enumerate_rfnoc_blocks(              );              UHD_DEVICE3_LOG() << str(boost::format("Setting up NoC-Shell Control for port #%d (SID: %s)...") % port_number % xport1.send_sid.to_pp_string_hex());              uhd::rfnoc::ctrl_iface::sptr ctrl1 = uhd::rfnoc::ctrl_iface::make( -                    endianness == ENDIANNESS_BIG, +                    xport1.endianness == uhd::ENDIANNESS_BIG,                      xport1.send,                      xport1.recv,                      xport1.send_sid,                      str(boost::format("CE_%02d_Port_%02d") % i % ctrl_sid.get_dst_endpoint())              ); -            UHD_DEVICE3_LOG() << "OK" << std::endl; +            UHD_DEVICE3_LOG() << "OK" ;              make_args.ctrl_ifaces[port_number] = ctrl1;          }          make_args.base_address = xport.send_sid.get_dst();          make_args.device_index = device_index;          make_args.tree = subtree; -        make_args.is_big_endian = (endianness == ENDIANNESS_BIG); -        _rfnoc_block_ctrl.push_back(uhd::rfnoc::block_ctrl_base::make(make_args, noc_id)); +        {   //Critical section for block_ctrl vector access +            boost::lock_guard<boost::mutex> lock(_block_ctrl_mutex); +            _rfnoc_block_ctrl.push_back(uhd::rfnoc::block_ctrl_base::make(make_args, noc_id)); +        }      }  } diff --git a/host/lib/usrp/device3/device3_impl.hpp b/host/lib/usrp/device3/device3_impl.hpp index 117e4af1c..c2ec26f80 100644 --- a/host/lib/usrp/device3/device3_impl.hpp +++ b/host/lib/usrp/device3/device3_impl.hpp @@ -134,7 +134,6 @@ protected:      virtual uhd::device_addr_t get_tx_hints(size_t) { return uhd::device_addr_t(); };      virtual uhd::device_addr_t get_rx_hints(size_t) { return uhd::device_addr_t(); }; -    virtual uhd::endianness_t get_transport_endianness(size_t mb_index) = 0;      //! Is called after a streamer is generated      virtual void post_streamer_hooks(uhd::direction_t) {}; @@ -167,16 +166,12 @@ protected:              size_t n_blocks,              size_t base_port,              const uhd::sid_t &base_sid, -            uhd::device_addr_t transport_args, -            uhd::endianness_t endianness +            uhd::device_addr_t transport_args      );      /***********************************************************************       * Members       **********************************************************************/ -    //! A counter, designed to create unique SIDs -    size_t _sid_framer; -      // TODO: Maybe move these to private      uhd::dict<std::string, boost::weak_ptr<uhd::rx_streamer> > _rx_streamers;      uhd::dict<std::string, boost::weak_ptr<uhd::tx_streamer> > _tx_streamers; diff --git a/host/lib/usrp/device3/device3_io_impl.cpp b/host/lib/usrp/device3/device3_io_impl.cpp index 199cb2786..1668846c2 100644 --- a/host/lib/usrp/device3/device3_io_impl.cpp +++ b/host/lib/usrp/device3/device3_io_impl.cpp @@ -23,7 +23,7 @@  #include <uhd/rfnoc/sink_block_ctrl_base.hpp>  #include <uhd/utils/byteswap.hpp>  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> +  #include "../common/async_packet_handler.hpp"  #include "../../transport/super_recv_packet_handler.hpp"  #include "../../transport/super_send_packet_handler.hpp" @@ -34,7 +34,8 @@  #include <uhd/transport/zero_copy_flow_ctrl.hpp>  #include <boost/atomic.hpp> -#define UHD_STREAMER_LOG() UHD_LOGV(never) +#define UHD_TX_STREAMER_LOG() UHD_LOGGER_TRACE("STREAMER") +#define UHD_RX_STREAMER_LOG() UHD_LOGGER_TRACE("STREAMER")  using namespace uhd;  using namespace uhd::usrp; @@ -140,7 +141,7 @@ void generate_channel_list(      }      // Add all remaining args to all channel args -    BOOST_FOREACH(device_addr_t &chan_arg, chan_args_) { +    for(device_addr_t &chan_arg:  chan_args_) {          chan_arg = chan_arg.to_string() + "," + args.args.to_string();      } @@ -251,7 +252,7 @@ static void handle_rx_flowctrl(      // Super-verbose mode:      //static size_t fc_pkt_count = 0; -    //UHD_MSG(status) << "sending flow ctrl packet " << fc_pkt_count++ << ", acking " << str(boost::format("%04d\tseq_sw==0x%08x") % last_seq % seq32) << std::endl; +    //UHD_LOGGER_INFO("STREAMER") << "sending flow ctrl packet " << fc_pkt_count++ << ", acking " << str(boost::format("%04d\tseq_sw==0x%08x") % last_seq % seq32) ;      //load packet info      vrt::if_packet_info_t packet_info; @@ -445,7 +446,7 @@ static void handle_tx_async_msgs(      }      catch(const std::exception &ex)      { -        UHD_MSG(error) << "Error parsing async message packet: " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("STREAMER") << "Error parsing async message packet: " << ex.what() ;          return;      } @@ -499,8 +500,8 @@ bool device3_impl::recv_async_msg(   **********************************************************************/  void device3_impl::update_rx_streamers(double /* rate */)  { -    BOOST_FOREACH(const std::string &block_id, _rx_streamers.keys()) { -        UHD_STREAMER_LOG() << "[Device3] updating RX streamer to " << block_id << std::endl; +    for(const std::string &block_id:  _rx_streamers.keys()) { +        UHD_RX_STREAMER_LOG() << "updating RX streamer to " << block_id;          boost::shared_ptr<sph::recv_packet_streamer> my_streamer =              boost::dynamic_pointer_cast<sph::recv_packet_streamer>(_rx_streamers[block_id].lock());          if (my_streamer) { @@ -517,7 +518,7 @@ void device3_impl::update_rx_streamers(double /* rate */)              if (scaling == rfnoc::scalar_node_ctrl::SCALE_UNDEFINED) {                  scaling = 1/32767.;              } -            UHD_STREAMER_LOG() << "  New tick_rate == " << tick_rate << "  New samp_rate == " << samp_rate << " New scaling == " << scaling << std::endl; +            UHD_RX_STREAMER_LOG() << "  New tick_rate == " << tick_rate << "  New samp_rate == " << samp_rate << " New scaling == " << scaling ;              my_streamer->set_tick_rate(tick_rate);              my_streamer->set_samp_rate(samp_rate); @@ -546,7 +547,7 @@ rx_streamer::sptr device3_impl::get_rx_stream(const stream_args_t &args_)      for (size_t stream_i = 0; stream_i < chan_list.size(); stream_i++) {          // Get block ID and mb index          uhd::rfnoc::block_id_t block_id = chan_list[stream_i]; -        UHD_STREAMER_LOG() << "[RX Streamer] chan " << stream_i << " connecting to " << block_id << std::endl; +        UHD_RX_STREAMER_LOG() << "chan " << stream_i << " connecting to " << block_id ;          // Update args so args.args is always valid for this particular channel:          args.args = chan_args[stream_i];          size_t mb_index = block_id.get_device_no(); @@ -574,20 +575,20 @@ rx_streamer::sptr device3_impl::get_rx_stream(const stream_args_t &args_)          //allocate sid and create transport          uhd::sid_t stream_address = blk_ctrl->get_address(block_port); -        UHD_STREAMER_LOG() << "[RX Streamer] creating rx stream " << rx_hints.to_string() << std::endl; +        UHD_RX_STREAMER_LOG() << "creating rx stream " << rx_hints.to_string() ;          both_xports_t xport = make_transport(stream_address, RX_DATA, rx_hints); -        UHD_STREAMER_LOG() << std::hex << "[RX Streamer] data_sid = " << xport.send_sid << std::dec << " actual recv_buff_size = " << xport.recv_buff_size << std::endl; +        UHD_RX_STREAMER_LOG() << std::hex << "data_sid = " << xport.send_sid << std::dec << " actual recv_buff_size = " << xport.recv_buff_size ;          // Configure the block          blk_ctrl->set_destination(xport.send_sid.get_src(), block_port);          blk_ctrl->sr_write(uhd::rfnoc::SR_RESP_OUT_DST_SID, xport.send_sid.get_src(), block_port); -        UHD_STREAMER_LOG() << "[RX Streamer] resp_out_dst_sid == " << xport.send_sid.get_src() << std::endl; +        UHD_RX_STREAMER_LOG() << "resp_out_dst_sid == " << xport.send_sid.get_src() ;          // Find all upstream radio nodes and set their response in SID to the host          std::vector<boost::shared_ptr<uhd::rfnoc::radio_ctrl> > upstream_radio_nodes = blk_ctrl->find_upstream_node<uhd::rfnoc::radio_ctrl>(); -        UHD_STREAMER_LOG() << "[RX Streamer] Number of upstream radio nodes: " << upstream_radio_nodes.size() << std::endl; -        BOOST_FOREACH(const boost::shared_ptr<uhd::rfnoc::radio_ctrl> &node, upstream_radio_nodes) { +        UHD_RX_STREAMER_LOG() << "Number of upstream radio nodes: " << upstream_radio_nodes.size(); +        for(const boost::shared_ptr<uhd::rfnoc::radio_ctrl> &node:  upstream_radio_nodes) {              node->sr_write(uhd::rfnoc::SR_RESP_OUT_DST_SID, xport.send_sid.get_src(), block_port);          } @@ -596,7 +597,7 @@ rx_streamer::sptr device3_impl::get_rx_stream(const stream_args_t &args_)          const size_t bpp = xport.recv->get_recv_frame_size() - stream_options.rx_max_len_hdr; // bytes per packet          const size_t bpi = convert::get_bytes_per_item(args.otw_format); // bytes per item          const size_t spp = std::min(args.args.cast<size_t>("spp", bpp/bpi), bpp/bpi); // samples per packet -        UHD_STREAMER_LOG() << "[RX Streamer] spp == " << spp << std::endl; +        UHD_RX_STREAMER_LOG() << "spp == " << spp ;          //make the new streamer given the samples per packet          if (not my_streamer) @@ -605,7 +606,7 @@ rx_streamer::sptr device3_impl::get_rx_stream(const stream_args_t &args_)          //init some streamer stuff          std::string conv_endianness; -        if (get_transport_endianness(mb_index) == ENDIANNESS_BIG) { +        if (xport.endianness == ENDIANNESS_BIG) {              my_streamer->set_vrt_unpacker(&vrt::chdr::if_hdr_unpack_be);              conv_endianness = "be";          } else { @@ -625,7 +626,7 @@ rx_streamer::sptr device3_impl::get_rx_stream(const stream_args_t &args_)          const size_t pkt_size = spp * bpi + stream_options.rx_max_len_hdr;          const size_t fc_window = get_rx_flow_control_window(pkt_size, xport.recv_buff_size, rx_hints);          const size_t fc_handle_window = std::max<size_t>(1, fc_window / stream_options.rx_fc_request_freq); -        UHD_STREAMER_LOG()<< "[RX Streamer] Flow Control Window (minus one) = " << fc_window-1 << ", Flow Control Handler Window = " << fc_handle_window << std::endl; +        UHD_RX_STREAMER_LOG()<< "Flow Control Window (minus one) = " << fc_window-1 << ", Flow Control Handler Window = " << fc_handle_window ;          blk_ctrl->configure_flow_control_out(                  fc_window-1, // Leave one space for overrun packets TODO make this obsolete                  block_port @@ -658,7 +659,7 @@ rx_streamer::sptr device3_impl::get_rx_stream(const stream_args_t &args_)                  &handle_rx_flowctrl,                  xport.send_sid,                  xport.send, -                get_transport_endianness(mb_index), +                xport.endianness,                  fc_cache,                  _1              ), @@ -701,8 +702,8 @@ rx_streamer::sptr device3_impl::get_rx_stream(const stream_args_t &args_)   **********************************************************************/  void device3_impl::update_tx_streamers(double /* rate */)  { -    BOOST_FOREACH(const std::string &block_id, _tx_streamers.keys()) { -        UHD_STREAMER_LOG() << "[Device3] updating TX streamer: " << block_id << std::endl; +    for(const std::string &block_id:  _tx_streamers.keys()) { +        UHD_TX_STREAMER_LOG() << "updating TX streamer: " << block_id;          boost::shared_ptr<sph::send_packet_streamer> my_streamer =              boost::dynamic_pointer_cast<sph::send_packet_streamer>(_tx_streamers[block_id].lock());          if (my_streamer) { @@ -718,7 +719,7 @@ void device3_impl::update_tx_streamers(double /* rate */)              if (scaling == rfnoc::scalar_node_ctrl::SCALE_UNDEFINED) {                  scaling = 32767.;              } -            UHD_STREAMER_LOG() << "  New tick_rate == " << tick_rate << "  New samp_rate == " << samp_rate << " New scaling == " << scaling << std::endl; +            UHD_TX_STREAMER_LOG() << "New tick_rate == " << tick_rate << "  New samp_rate == " << samp_rate << " New scaling == " << scaling ;              my_streamer->set_tick_rate(tick_rate);              my_streamer->set_samp_rate(samp_rate);              my_streamer->set_scale_factor(scaling); @@ -777,16 +778,16 @@ tx_streamer::sptr device3_impl::get_tx_stream(const uhd::stream_args_t &args_)          //allocate sid and create transport          uhd::sid_t stream_address = blk_ctrl->get_address(block_port); -        UHD_STREAMER_LOG() << "[TX Streamer] creating tx stream " << tx_hints.to_string() << std::endl; +        UHD_TX_STREAMER_LOG() << "creating tx stream " << tx_hints.to_string() ;          both_xports_t xport = make_transport(stream_address, TX_DATA, tx_hints); -        UHD_STREAMER_LOG() << std::hex << "[TX Streamer] data_sid = " << xport.send_sid << std::dec << std::endl; +        UHD_TX_STREAMER_LOG() << std::hex << "data_sid = " << xport.send_sid << std::dec ;          // To calculate the max number of samples per packet, we assume the maximum header length          // to avoid fragmentation should the entire header be used.          const size_t bpp = tx_hints.cast<size_t>("bpp", xport.send->get_send_frame_size()) - stream_options.tx_max_len_hdr;          const size_t bpi = convert::get_bytes_per_item(args.otw_format); // bytes per item          const size_t spp = std::min(args.args.cast<size_t>("spp", bpp/bpi), bpp/bpi); // samples per packet -        UHD_STREAMER_LOG() << "[TX Streamer] spp == " << spp << std::endl; +        UHD_TX_STREAMER_LOG() << "spp == " << spp ;          //make the new streamer given the samples per packet          if (not my_streamer) @@ -795,7 +796,7 @@ tx_streamer::sptr device3_impl::get_tx_stream(const uhd::stream_args_t &args_)          //init some streamer stuff          std::string conv_endianness; -        if (get_transport_endianness(mb_index) == ENDIANNESS_BIG) { +        if (xport.endianness == ENDIANNESS_BIG) {              my_streamer->set_vrt_packer(&vrt::chdr::if_hdr_pack_be);              conv_endianness = "be";          } else { @@ -820,7 +821,7 @@ tx_streamer::sptr device3_impl::get_tx_stream(const uhd::stream_args_t &args_)                  tx_hints // This can override the value reported by the block!          );          const size_t fc_handle_window = std::max<size_t>(1, fc_window / stream_options.tx_fc_response_freq); -        UHD_STREAMER_LOG() << "[TX Streamer] Flow Control Window = " << fc_window << ", Flow Control Handler Window = " << fc_handle_window << std::endl; +        UHD_TX_STREAMER_LOG() << "Flow Control Window = " << fc_window << ", Flow Control Handler Window = " << fc_handle_window ;          blk_ctrl->configure_flow_control_in(                  stream_options.tx_fc_response_cycles,                  fc_handle_window, /*pkts*/ @@ -843,14 +844,14 @@ tx_streamer::sptr device3_impl::get_tx_stream(const uhd::stream_args_t &args_)                      &handle_tx_async_msgs,                      fc_cache,                      xport.recv, -                    get_transport_endianness(mb_index), +                    xport.endianness,                      tick_rate_retriever                  )          );          blk_ctrl->sr_write(uhd::rfnoc::SR_CLEAR_RX_FC, 0xc1ea12, block_port);          blk_ctrl->sr_write(uhd::rfnoc::SR_RESP_IN_DST_SID, xport.recv_sid.get_dst(), block_port); -        UHD_STREAMER_LOG() << "[TX Streamer] resp_in_dst_sid == " << boost::format("0x%04X") % xport.recv_sid.get_dst() << std::endl; +        UHD_TX_STREAMER_LOG() << "resp_in_dst_sid == " << boost::format("0x%04X") % xport.recv_sid.get_dst() ;          // FIXME: Once there is a better way to map the radio block and port          // to the channel or another way to receive asynchronous messages that @@ -861,8 +862,8 @@ tx_streamer::sptr device3_impl::get_tx_stream(const uhd::stream_args_t &args_)              uhd::rfnoc::block_id_t radio_id(args.args["radio_id"]);              size_t radio_port = args.args.cast<size_t>("radio_port", 0);              std::vector<boost::shared_ptr<uhd::rfnoc::radio_ctrl> > downstream_radio_nodes = blk_ctrl->find_downstream_node<uhd::rfnoc::radio_ctrl>(); -            UHD_STREAMER_LOG() << "[TX Streamer] Number of downstream radio nodes: " << downstream_radio_nodes.size() << std::endl; -            BOOST_FOREACH(const boost::shared_ptr<uhd::rfnoc::radio_ctrl> &node, downstream_radio_nodes) { +            UHD_TX_STREAMER_LOG() << "Number of downstream radio nodes: " << downstream_radio_nodes.size(); +            for(const boost::shared_ptr<uhd::rfnoc::radio_ctrl> &node:  downstream_radio_nodes) {                  if (node->get_block_id() == radio_id) {                      node->sr_write(uhd::rfnoc::SR_RESP_IN_DST_SID, xport.send_sid.get_src(), radio_port);                  } @@ -875,8 +876,8 @@ tx_streamer::sptr device3_impl::get_tx_stream(const uhd::stream_args_t &args_)              // soon as possible.              // Find all downstream radio nodes and set their response SID to the host              std::vector<boost::shared_ptr<uhd::rfnoc::radio_ctrl> > downstream_radio_nodes = blk_ctrl->find_downstream_node<uhd::rfnoc::radio_ctrl>(); -            UHD_STREAMER_LOG() << "[TX Streamer] Number of downstream radio nodes: " << downstream_radio_nodes.size() << std::endl; -            BOOST_FOREACH(const boost::shared_ptr<uhd::rfnoc::radio_ctrl> &node, downstream_radio_nodes) { +            UHD_TX_STREAMER_LOG() << "Number of downstream radio nodes: " << downstream_radio_nodes.size(); +            for(const boost::shared_ptr<uhd::rfnoc::radio_ctrl> &node:  downstream_radio_nodes) {                  node->sr_write(uhd::rfnoc::SR_RESP_IN_DST_SID, xport.send_sid.get_src(), block_port);              }          } @@ -885,7 +886,8 @@ tx_streamer::sptr device3_impl::get_tx_stream(const uhd::stream_args_t &args_)          xport.send = zero_copy_flow_ctrl::make(              xport.send,              boost::bind(&tx_flow_ctrl, task, fc_cache, fc_window, _1), -            NULL); +            0 +        );          //Give the streamer a functor to get the send buffer          //get_tx_buff is static so bind has no lifetime issues diff --git a/host/lib/usrp/e100/clock_ctrl.cpp b/host/lib/usrp/e100/clock_ctrl.cpp index 0dbd6a5d3..a3f630462 100644 --- a/host/lib/usrp/e100/clock_ctrl.cpp +++ b/host/lib/usrp/e100/clock_ctrl.cpp @@ -17,13 +17,12 @@  #include "clock_ctrl.hpp"  #include "ad9522_regs.hpp" -#include <uhd/utils/msg.hpp> +  #include <uhd/utils/log.hpp>  #include <uhd/utils/assert_has.hpp>  #include <stdint.h>  #include "e100_regs.hpp" //spi slave constants  #include <boost/assign/list_of.hpp> -#include <boost/foreach.hpp>  #include <boost/format.hpp>  #include <boost/thread/thread.hpp>  #include <boost/math/common_factor_rt.hpp> //gcd @@ -137,11 +136,11 @@ static clock_settings_type get_clock_settings(double rate){                  cs.chan_divider /= cs.vco_divider;              } -            UHD_LOGV(always) -                << "gcd " << gcd << std::endl -                << "X " << X << std::endl -                << "Y " << Y << std::endl -                << cs.to_pp_string() << std::endl +            UHD_LOGGER_DEBUG("E100") +                << "gcd: " << gcd +                << " X: " << X +                << " Y: " << Y +                << cs.to_pp_string()              ;              //filter limits on the counters @@ -155,7 +154,7 @@ static clock_settings_type get_clock_settings(double rate){              if (cs.get_vco_rate() < 1400e6 + vco_bound_pad) continue;              if (cs.get_out_rate() != rate) continue; -            UHD_MSG(status) << "USRP-E100 clock control: " << i << std::endl << cs.to_pp_string() << std::endl; +            UHD_LOGGER_INFO("E100") << "USRP-E100 clock control: " << i  << cs.to_pp_string() ;              return cs;          }      } @@ -195,7 +194,7 @@ public:          this->use_internal_ref();          //initialize the FPGA clock rate -        UHD_MSG(status) << boost::format("Initializing FPGA clock to %fMHz...") % (master_clock_rate/1e6) << std::endl; +        UHD_LOGGER_INFO("E100") << boost::format("Initializing FPGA clock to %fMHz...") % (master_clock_rate/1e6) ;          this->set_fpga_clock_rate(master_clock_rate);          this->enable_test_clock(ENABLE_THE_TEST_OUT); @@ -460,7 +459,7 @@ private:      void send_reg(uint16_t addr){          uint32_t reg = _ad9522_regs.get_write_reg(addr); -        UHD_LOGV(often) << "clock control write reg: " << std::hex << reg << std::endl; +        UHD_LOGGER_TRACE("E100") << "clock control write reg: " << std::hex << reg ;          _iface->write_spi(              UE_SPI_SS_AD9522,              spi_config_t::EDGE_RISE, @@ -487,7 +486,7 @@ private:              _ad9522_regs.set_reg(addr, reg);              if (_ad9522_regs.vco_calibration_finished) goto wait_for_ld;          } -        UHD_MSG(error) << "USRP-E100 clock control: VCO calibration timeout" << std::endl; +        UHD_LOGGER_ERROR("E100") << "USRP-E100 clock control: VCO calibration timeout" ;          wait_for_ld:          //wait for digital lock detect:          for (size_t ms10 = 0; ms10 < 100; ms10++){ @@ -499,7 +498,7 @@ private:              _ad9522_regs.set_reg(addr, reg);              if (_ad9522_regs.digital_lock_detect) return;          } -        UHD_MSG(error) << "USRP-E100 clock control: lock detection timeout" << std::endl; +        UHD_LOGGER_ERROR("E100") << "USRP-E100 clock control: lock detection timeout" ;      }      void soft_sync(void){ @@ -521,7 +520,7 @@ private:          ;          //write initial register values and latch/update -        BOOST_FOREACH(const range_t &range, ranges){ +        for(const range_t &range:  ranges){              for(uint16_t addr = range.first; addr <= range.second; addr++){                  this->send_reg(addr);              } diff --git a/host/lib/usrp/e100/codec_ctrl.cpp b/host/lib/usrp/e100/codec_ctrl.cpp index 7dce01e46..5bd394fb1 100644 --- a/host/lib/usrp/e100/codec_ctrl.cpp +++ b/host/lib/usrp/e100/codec_ctrl.cpp @@ -260,7 +260,7 @@ void e100_codec_ctrl_impl::write_aux_dac(aux_dac_t which, double volts){   **********************************************************************/  void e100_codec_ctrl_impl::send_reg(uint8_t addr){      uint32_t reg = _ad9862_regs.get_write_reg(addr); -    UHD_LOGV(often) << "codec control write reg: " << std::hex << reg << std::endl; +    UHD_LOGGER_TRACE("E100") << "codec control write reg: " << std::hex << reg ;      _iface->write_spi(          UE_SPI_SS_AD9862,          spi_config_t::EDGE_RISE, @@ -270,13 +270,13 @@ void e100_codec_ctrl_impl::send_reg(uint8_t addr){  void e100_codec_ctrl_impl::recv_reg(uint8_t addr){      uint32_t reg = _ad9862_regs.get_read_reg(addr); -    UHD_LOGV(often) << "codec control read reg: " << std::hex << reg << std::endl; +    UHD_LOGGER_TRACE("E100") << "codec control read reg: " << std::hex << reg ;      uint32_t ret = _iface->read_spi(          UE_SPI_SS_AD9862,          spi_config_t::EDGE_RISE,          reg, 16      ); -    UHD_LOGV(often) << "codec control read ret: " << std::hex << ret << std::endl; +    UHD_LOGGER_TRACE("E100") << "codec control read ret: " << std::hex << ret ;      _ad9862_regs.set_reg(addr, uint16_t(ret));  } diff --git a/host/lib/usrp/e100/e100_ctrl.cpp b/host/lib/usrp/e100/e100_ctrl.cpp index 4217286f8..41525300c 100644 --- a/host/lib/usrp/e100/e100_ctrl.cpp +++ b/host/lib/usrp/e100/e100_ctrl.cpp @@ -19,7 +19,7 @@  #include "e100_regs.hpp"  #include <uhd/exception.hpp>  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> +  #include <sys/ioctl.h> //ioctl  #include <fcntl.h> //open, close  #include <linux/usrp_e.h> //ioctl structures and constants @@ -27,7 +27,6 @@  #include <boost/thread/thread.hpp> //sleep  #include <boost/thread/mutex.hpp>  #include <boost/thread/condition_variable.hpp> -#include <boost/foreach.hpp>  #include <boost/format.hpp>  #include <fstream> @@ -219,7 +218,7 @@ public:      void write_uart(const std::string &buf){          const ssize_t ret = ::write(_node_fd, buf.c_str(), buf.size()); -        if (size_t(ret) != buf.size()) UHD_LOG << ret; +        if (size_t(ret) != buf.size()) UHD_LOGGER_DEBUG("E100")<< ret;      }      std::string read_uart(double timeout){ @@ -330,7 +329,7 @@ public:       * Structors       ******************************************************************/      e100_ctrl_impl(const std::string &node){ -        UHD_MSG(status) << "Opening device node " << node << "..." << std::endl; +        UHD_LOGGER_INFO("E100") << "Opening device node " << node << "..." ;          //open the device node and check file descriptor          if ((_node_fd = ::open(node.c_str(), O_RDWR)) < 0){ @@ -350,7 +349,7 @@ public:          edge_file << "rising" << std::endl << std::flush;          edge_file.close();          _irq_fd = ::open("/sys/class/gpio/gpio147/value", O_RDONLY); -        if (_irq_fd < 0) UHD_MSG(error) << "Unable to open GPIO for IRQ\n"; +        if (_irq_fd < 0) UHD_LOGGER_ERROR("E100") << "Unable to open GPIO for IRQ\n";      }      ~e100_ctrl_impl(void){ diff --git a/host/lib/usrp/e100/e100_impl.cpp b/host/lib/usrp/e100/e100_impl.cpp index 25c967cfa..ddb21fc35 100644 --- a/host/lib/usrp/e100/e100_impl.cpp +++ b/host/lib/usrp/e100/e100_impl.cpp @@ -18,7 +18,7 @@  #include "apply_corrections.hpp"  #include "e100_impl.hpp"  #include "e100_regs.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/static.hpp>  #include <uhd/utils/paths.hpp> @@ -140,7 +140,7 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){          e100_fpga_image = find_image_path(device_addr.get("fpga", default_fpga_file_name));      }      catch(...){ -        UHD_MSG(error) << boost::format("Could not find FPGA image. %s\n") % print_utility_error("uhd_images_downloader.py"); +        UHD_LOGGER_ERROR("E100") << boost::format("Could not find FPGA image. %s") % print_utility_error("uhd_images_downloader.py");          throw;      }      e100_load_fpga(e100_fpga_image); @@ -151,10 +151,10 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      bool dboard_clocks_diff = true;      if      (mb_eeprom.get("revision", "0") == "3") dboard_clocks_diff = false;      else if (mb_eeprom.get("revision", "0") == "4") dboard_clocks_diff = true; -    else UHD_MSG(warning) +    else UHD_LOGGER_WARNING("E100")          << "Unknown E1XX revision number!\n"          << "defaulting to differential dboard clocks to be safe.\n" -        << std::endl; +        ;      const double master_clock_rate = device_addr.cast<double>("master_clock_rate", E100_DEFAULT_CLOCK_RATE);      _aux_spi_iface = e100_ctrl::make_aux_spi_iface();      _clock_ctrl = e100_clock_ctrl::make(_aux_spi_iface, master_clock_rate, dboard_clocks_diff); @@ -179,7 +179,7 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      //Perform wishbone readback tests, these tests also write the hash      bool test_fail = false; -    UHD_MSG(status) << "Performing control readback test... " << std::flush; +    UHD_LOGGER_INFO("E100") << "Performing control readback test... ";      size_t hash = time(NULL);      for (size_t i = 0; i < 100; i++){          boost::hash_combine(hash, i); @@ -187,12 +187,12 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){          test_fail = _fifo_ctrl->peek32(REG_RB_CONFIG0) != uint32_t(hash);          if (test_fail) break; //exit loop on any failure      } -    UHD_MSG(status) << ((test_fail)? " fail" : "pass") << std::endl; +    UHD_LOGGER_INFO("E100") << "Control readback test " << ((test_fail)? "failed" : "passed"); -    if (test_fail) UHD_MSG(error) << boost::format( -        "The FPGA is either clocked improperly\n" -        "or the FPGA build is not compatible.\n" -        "Subsequent errors may follow...\n" +    if (test_fail) UHD_LOGGER_ERROR("E100") << boost::format( +        "The FPGA is either clocked improperly " +        "or the FPGA build is not compatible. " +        "Subsequent errors may follow..."      );      //check that the compatibility is correct @@ -260,16 +260,16 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      static const fs::path GPSDO_VOLATILE_PATH("/media/ram/e100_internal_gpsdo.cache");      if (not fs::exists(GPSDO_VOLATILE_PATH))      { -        UHD_MSG(status) << "Detecting internal GPSDO.... " << std::flush; +        UHD_LOGGER_INFO("E100") << "Detecting internal GPSDO.... ";          try{              _gps = gps_ctrl::make(e100_ctrl::make_gps_uart_iface(E100_UART_DEV_NODE));          }          catch(std::exception &e){ -            UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl; +            UHD_LOGGER_ERROR("E100") << "An error occurred making GPSDO control: " << e.what();          }          if (_gps and _gps->gps_detected())          { -            BOOST_FOREACH(const std::string &name, _gps->get_sensors()) +            for(const std::string &name:  _gps->get_sensors())              {                  _tree->create<sensor_value_t>(mb_path / "sensors" / name)                      .set_publisher(boost::bind(&gps_ctrl::get_sensor, _gps, name)); @@ -434,12 +434,12 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      //bind frontend corrections to the dboard freq props      const fs_path db_tx_fe_path = mb_path / "dboards" / "A" / "tx_frontends"; -    BOOST_FOREACH(const std::string &name, _tree->list(db_tx_fe_path)){ +    for(const std::string &name:  _tree->list(db_tx_fe_path)){          _tree->access<double>(db_tx_fe_path / name / "freq" / "value")              .add_coerced_subscriber(boost::bind(&e100_impl::set_tx_fe_corrections, this, _1));      }      const fs_path db_rx_fe_path = mb_path / "dboards" / "A" / "rx_frontends"; -    BOOST_FOREACH(const std::string &name, _tree->list(db_rx_fe_path)){ +    for(const std::string &name:  _tree->list(db_rx_fe_path)){          _tree->access<double>(db_rx_fe_path / name / "freq" / "value")              .add_coerced_subscriber(boost::bind(&e100_impl::set_rx_fe_corrections, this, _1));      } @@ -460,10 +460,10 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){          .add_coerced_subscriber(boost::bind(&e100_clock_ctrl::set_fpga_clock_rate, _clock_ctrl, _1));      //reset cordic rates and their properties to zero -    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){ +    for(const std::string &name:  _tree->list(mb_path / "rx_dsps")){          _tree->access<double>(mb_path / "rx_dsps" / name / "freq" / "value").set(0.0);      } -    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +    for(const std::string &name:  _tree->list(mb_path / "tx_dsps")){          _tree->access<double>(mb_path / "tx_dsps" / name / "freq" / "value").set(0.0);      } @@ -475,10 +475,10 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      //GPS installed: use external ref, time, and init time spec      if (_gps and _gps->gps_detected()){          _time64->enable_gpsdo(); -        UHD_MSG(status) << "Setting references to the internal GPSDO" << std::endl; +        UHD_LOGGER_INFO("E100") << "Setting references to the internal GPSDO";          _tree->access<std::string>(mb_path / "time_source/value").set("gpsdo");          _tree->access<std::string>(mb_path / "clock_source/value").set("gpsdo"); -        UHD_MSG(status) << "Initializing time to the internal GPSDO" << std::endl; +        UHD_LOGGER_INFO("E100") << "Initializing time to the internal GPSDO";          _time64->set_time_next_pps(time_spec_t(time_t(_gps->get_sensor("gps_time").to_int()+1)));      } diff --git a/host/lib/usrp/e100/e100_mmap_zero_copy.cpp b/host/lib/usrp/e100/e100_mmap_zero_copy.cpp index 57e4e32d9..37a87a669 100644 --- a/host/lib/usrp/e100/e100_mmap_zero_copy.cpp +++ b/host/lib/usrp/e100/e100_mmap_zero_copy.cpp @@ -42,14 +42,14 @@ public:          _mem(mem), _info(info) { /* NOP */ }      void release(void){ -        if (fp_verbose) UHD_LOGV(always) << "recv buff: release" << std::endl; +        if (fp_verbose) UHD_LOGGER_DEBUG("E100") << "recv buff: release" ;          _info->flags = RB_KERNEL; //release the frame      }      UHD_INLINE bool ready(void){return _info->flags & RB_USER;}      UHD_INLINE sptr get_new(void){ -        if (fp_verbose) UHD_LOGV(always) << "  make_recv_buff: " << _info->len << std::endl; +        if (fp_verbose) UHD_LOGGER_DEBUG("E100") << "  make_recv_buff: " << _info->len ;          _info->flags = RB_USER_PROCESS; //claim the frame          return make(this, _mem, _info->len);      } @@ -69,18 +69,18 @@ public:          _mem(mem), _info(info), _len(len), _fd(fd) { /* NOP */ }      void release(void){ -        if (fp_verbose) UHD_LOGV(always) << "send buff: commit " << size() << std::endl; +        if (fp_verbose) UHD_LOGGER_DEBUG("E100") << "send buff: commit " << size() ;          _info->len = _len;//size();          _info->flags = RB_USER; //release the frame          if (::write(_fd, NULL, 0) < 0){ //notifies the kernel -            UHD_LOGV(rarely) << UHD_THROW_SITE_INFO("write error") << std::endl; +            UHD_LOGGER_ERROR("E100") << UHD_THROW_SITE_INFO("write error") ;          }      }      UHD_INLINE bool ready(void){return _info->flags & RB_KERNEL;}      UHD_INLINE sptr get_new(void){ -        if (fp_verbose) UHD_LOGV(always) << "  make_send_buff: " << _len << std::endl; +        if (fp_verbose) UHD_LOGGER_DEBUG("E100") << "  make_send_buff: " << _len ;          _info->flags = RB_USER_PROCESS; //claim the frame          return make(this, _mem, _len);      } @@ -111,15 +111,13 @@ public:              (_rb_size.num_rx_frames + _rb_size.num_tx_frames) * _frame_size;          //print sizes summary -        UHD_LOG -            << "page_size:          " << page_size                   << std::endl -            << "frame_size:         " << _frame_size                 << std::endl -            << "num_pages_rx_flags: " << _rb_size.num_pages_rx_flags << std::endl -            << "num_rx_frames:      " << _rb_size.num_rx_frames      << std::endl -            << "num_pages_tx_flags: " << _rb_size.num_pages_tx_flags << std::endl -            << "num_tx_frames:      " << _rb_size.num_tx_frames      << std::endl -            << "map_size:           " << _map_size                   << std::endl -        ; +        UHD_LOGGER_DEBUG("E100") << "page_size:          " << page_size; +        UHD_LOGGER_DEBUG("E100") << "frame_size:         " << _frame_size; +        UHD_LOGGER_DEBUG("E100") << "num_pages_rx_flags: " << _rb_size.num_pages_rx_flags; +        UHD_LOGGER_DEBUG("E100") << "num_rx_frames:      " << _rb_size.num_rx_frames; +        UHD_LOGGER_DEBUG("E100") << "num_pages_tx_flags: " << _rb_size.num_pages_tx_flags; +        UHD_LOGGER_DEBUG("E100") << "num_tx_frames:      " << _rb_size.num_tx_frames; +        UHD_LOGGER_DEBUG("E100") << "map_size:           " << _map_size;          //call mmap to get the memory          _mapped_mem = ::mmap( @@ -134,12 +132,10 @@ public:          size_t send_buff_off = send_info_off + (_rb_size.num_pages_tx_flags * page_size);          //print offset summary -        UHD_LOG -            << "recv_info_off: " << recv_info_off << std::endl -            << "recv_buff_off: " << recv_buff_off << std::endl -            << "send_info_off: " << send_info_off << std::endl -            << "send_buff_off: " << send_buff_off << std::endl -        ; +        UHD_LOGGER_DEBUG("E100") << "recv_info_off: " << recv_info_off; +        UHD_LOGGER_DEBUG("E100") << "recv_buff_off: " << recv_buff_off; +        UHD_LOGGER_DEBUG("E100") << "send_info_off: " << send_info_off; +        UHD_LOGGER_DEBUG("E100") << "send_buff_off: " << send_buff_off;          //pointers to sections in the mapped memory          ring_buffer_info (*recv_info)[], (*send_info)[]; @@ -170,12 +166,12 @@ public:      }      ~e100_mmap_zero_copy_impl(void){ -        UHD_LOG << "cleanup: munmap" << std::endl; +        UHD_LOGGER_DEBUG("E100")<< "cleanup: munmap" ;          ::munmap(_mapped_mem, _map_size);      }      managed_recv_buffer::sptr get_recv_buff(double timeout){ -        if (fp_verbose) UHD_LOGV(always) << "get_recv_buff: " << _recv_index << std::endl; +        if (fp_verbose) UHD_LOGGER_DEBUG("E100") << "get_recv_buff: " << _recv_index ;          e100_mmap_zero_copy_mrb &mrb = *_mrb_pool[_recv_index];          //poll/wait for a ready frame @@ -185,7 +181,7 @@ public:                  pfd.fd = _fd;                  pfd.events = POLLIN;                  ssize_t poll_ret = ::poll(&pfd, 1, size_t(timeout*1e3/poll_breakout)); -                if (fp_verbose) UHD_LOGV(always) << "  POLLIN: " << poll_ret << std::endl; +                if (fp_verbose) UHD_LOGGER_DEBUG("E100") << "  POLLIN: " << poll_ret ;                  if (poll_ret > 0) goto found_user_frame; //good poll, continue on              }              return managed_recv_buffer::sptr(); //timed-out for real @@ -207,7 +203,7 @@ public:      }      managed_send_buffer::sptr get_send_buff(double timeout){ -        if (fp_verbose) UHD_LOGV(always) << "get_send_buff: " << _send_index << std::endl; +        if (fp_verbose) UHD_LOGGER_DEBUG("E100") << "get_send_buff: " << _send_index ;          e100_mmap_zero_copy_msb &msb = *_msb_pool[_send_index];          //poll/wait for a ready frame @@ -216,7 +212,7 @@ public:              pfd.fd = _fd;              pfd.events = POLLOUT;              ssize_t poll_ret = ::poll(&pfd, 1, size_t(timeout*1e3)); -            if (fp_verbose) UHD_LOGV(always) << "  POLLOUT: " << poll_ret << std::endl; +            if (fp_verbose) UHD_LOGGER_DEBUG("E100") << "  POLLOUT: " << poll_ret ;              if (poll_ret <= 0) return managed_send_buffer::sptr();          } diff --git a/host/lib/usrp/e100/fpga_downloader.cpp b/host/lib/usrp/e100/fpga_downloader.cpp index 9abde32f7..bfb207f39 100644 --- a/host/lib/usrp/e100/fpga_downloader.cpp +++ b/host/lib/usrp/e100/fpga_downloader.cpp @@ -23,18 +23,13 @@  #include <uhd/device.hpp>  #include <uhd/image_loader.hpp>  #include <uhd/types/device_addr.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/paths.hpp>  #include <uhd/utils/static.hpp>  #include "e100_impl.hpp"  #else //special case when this file is externally included  #include <stdexcept>  #include <iostream> -#define UHD_MSG(type) std::cout -namespace uhd{ -    typedef std::runtime_error os_error; -    typedef std::runtime_error io_error; -}  #endif  #include <sstream> @@ -246,7 +241,7 @@ static void send_file_to_fpga(const std::string &file_name, gpio &error, gpio &d  			throw uhd::os_error("INIT_B went high, error occured.");  		if (!done.get_value()) -			UHD_MSG(status) << "Configuration complete." << std::endl; +			UHD_LOGGER_INFO("E100") << "Configuration complete.";  	} while (bitstream.gcount() == BUF_SIZE);  } @@ -260,20 +255,20 @@ void e100_load_fpga(const std::string &bin_file){  	gpio gpio_init_b(INIT_B, IN);  	gpio gpio_done  (DONE,   IN); -	UHD_MSG(status) << "Loading FPGA image: " << bin_file << "... " << std::flush; +	UHD_LOGGER_INFO("E100") << "Loading FPGA image: " << bin_file << "... ";  //	if(std::system("/sbin/rmmod usrp_e") != 0){ -//		UHD_MSG(warning) << "USRP-E100 FPGA downloader: could not unload usrp_e module" << std::endl; +//		UHD_LOGGER_WARNING("E100") << "USRP-E100 FPGA downloader: could not unload usrp_e module" ;  //	}  	prepare_fpga_for_configuration(gpio_prog_b, gpio_init_b); -	UHD_MSG(status) << "done = " << gpio_done.get_value() << std::endl; +	UHD_LOGGER_INFO("E100") << "done = " << gpio_done.get_value();  	send_file_to_fpga(bin_file, gpio_init_b, gpio_done);  //	if(std::system("/sbin/modprobe usrp_e") != 0){ -//		UHD_MSG(warning) << "USRP-E100 FPGA downloader: could not load usrp_e module" << std::endl; +//		UHD_LOGGER_WARNING("E100") << "USRP-E100 FPGA downloader: could not load usrp_e module" ;  //	}  } diff --git a/host/lib/usrp/e100/io_impl.cpp b/host/lib/usrp/e100/io_impl.cpp index ebed3614c..acd14f17b 100644 --- a/host/lib/usrp/e100/io_impl.cpp +++ b/host/lib/usrp/e100/io_impl.cpp @@ -20,7 +20,7 @@  #include "../../transport/super_recv_packet_handler.hpp"  #include "../../transport/super_send_packet_handler.hpp"  #include "e100_impl.hpp" -#include <uhd/utils/msg.hpp> +  #include <uhd/utils/log.hpp>  #include <uhd/utils/tasks.hpp>  #include <boost/bind.hpp> @@ -75,10 +75,10 @@ void e100_impl::update_rates(void){      _tree->access<double>(mb_path / "tick_rate").update();      //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")){ +    for(const std::string &name:  _tree->list(mb_path / "rx_dsps")){          _tree->access<double>(mb_path / "rx_dsps" / name / "rate" / "value").update();      } -    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +    for(const std::string &name:  _tree->list(mb_path / "tx_dsps")){          _tree->access<double>(mb_path / "tx_dsps" / name / "rate" / "value").update();      }  } diff --git a/host/lib/usrp/e300/e300_common.cpp b/host/lib/usrp/e300/e300_common.cpp index 216713bc6..61da3a2a2 100644 --- a/host/lib/usrp/e300/e300_common.cpp +++ b/host/lib/usrp/e300/e300_common.cpp @@ -15,7 +15,7 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  //  #include <uhd/image_loader.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/paths.hpp>  #include <uhd/utils/static.hpp> @@ -26,6 +26,7 @@  #include "e300_common.hpp"  #include <boost/filesystem.hpp> +#include <boost/noncopyable.hpp>  #include <fstream>  #include <string> @@ -39,7 +40,7 @@ void load_fpga_image(const std::string &path)      if (not boost::filesystem::exists("/dev/xdevcfg"))          ::system("mknod /dev/xdevcfg c 259 0"); -    UHD_MSG(status) << "Loading FPGA image: " << path << "..." << std::flush; +    UHD_LOGGER_INFO("E300") << "Loading FPGA image: " << path << "...";      std::ifstream fpga_file(path.c_str(), std::ios_base::binary);      UHD_ASSERT_THROW(fpga_file.good()); @@ -57,7 +58,7 @@ void load_fpga_image(const std::string &path)      fpga_file.close();      std::fclose(wfile); -    UHD_MSG(status) << " done" << std::endl; +    UHD_LOGGER_INFO("E300") << "FPGA image loaded";  }  static bool e300_image_loader(const image_loader::image_loader_args_t &image_loader_args) { diff --git a/host/lib/usrp/e300/e300_common.hpp b/host/lib/usrp/e300/e300_common.hpp index d9a0afd9e..c0cb9e2fd 100644 --- a/host/lib/usrp/e300/e300_common.hpp +++ b/host/lib/usrp/e300/e300_common.hpp @@ -18,6 +18,8 @@  #ifndef INCLUDED_E300_COMMON_HPP  #define INCLUDED_E300_COMMON_HPP +#include <string> +  namespace uhd { namespace usrp { namespace e300 {  namespace common { diff --git a/host/lib/usrp/e300/e300_defaults.hpp b/host/lib/usrp/e300/e300_defaults.hpp index 267897e03..cc810c0df 100644 --- a/host/lib/usrp/e300/e300_defaults.hpp +++ b/host/lib/usrp/e300/e300_defaults.hpp @@ -60,7 +60,7 @@ public:          }      }      clocking_mode_t get_clocking_mode() { -        return AD9361_XTAL_N_CLK_PATH; +        return clocking_mode_t::AD9361_XTAL_N_CLK_PATH;      }      digital_interface_mode_t get_digital_interface_mode() {          return AD9361_DDR_FDD_LVCMOS; diff --git a/host/lib/usrp/e300/e300_fifo_config.cpp b/host/lib/usrp/e300/e300_fifo_config.cpp index 4138bb581..c4c563af6 100644 --- a/host/lib/usrp/e300/e300_fifo_config.cpp +++ b/host/lib/usrp/e300/e300_fifo_config.cpp @@ -1,5 +1,5 @@  // -// Copyright 2013-2014 Ettus Research LLC +// Copyright 2013-2017 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 @@ -17,8 +17,9 @@  #ifdef E300_NATIVE -#include <stdint.h>  #include <uhd/config.hpp> +#include <stdint.h> +#include <atomic>  // constants coded into the fpga parameters  static const size_t ZF_CONFIG_BASE    = 0x40000000; @@ -81,7 +82,7 @@ static UHD_INLINE size_t ZF_STREAM_OFF(const size_t which)  #include <fcntl.h> //open, close  #include <poll.h> //poll  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> +  #include <boost/format.hpp>  #include <boost/thread/thread.hpp> //sleep  #include <uhd/types/time_spec.hpp> //timeout @@ -95,14 +96,19 @@ static UHD_INLINE size_t ZF_STREAM_OFF(const size_t which)  struct e300_fifo_poll_waiter  {      e300_fifo_poll_waiter(const int fd): -        fd(fd) +        fd(fd), +       _poll_claimed(false)      {          //NOP      } +    /*! +     * Waits until the file descriptor fd has data to read. +     * Access to the file descriptor is thread safe. +     */      void wait(const double timeout)      { -        if (_poll_claimed.cas(1, 0)) +        if (_poll_claimed.exchange(true))          {              boost::mutex::scoped_lock l(mutex);              cond.wait(l); @@ -116,12 +122,12 @@ struct e300_fifo_poll_waiter              if (fds[0].revents & POLLIN)                  ::read(fd, NULL, 0); -            _poll_claimed.write(0); +            _poll_claimed = false;              cond.notify_all();          }      } -    uhd::atomic_uint32_t _poll_claimed; +    std::atomic_bool _poll_claimed;      boost::condition_variable cond;      boost::mutex mutex;      int fd; @@ -202,9 +208,9 @@ public:          _index(0),          _waiter(waiter)      { -        //UHD_MSG(status) << boost::format("phys 0x%x") % addrs.phys << std::endl; -        //UHD_MSG(status) << boost::format("data 0x%x") % addrs.data << std::endl; -        //UHD_MSG(status) << boost::format("ctrl 0x%x") % addrs.ctrl << std::endl; +        //UHD_LOGGER_INFO("E300") << boost::format("phys 0x%x") % addrs.phys ; +        //UHD_LOGGER_INFO("E300") << boost::format("data 0x%x") % addrs.data ; +        //UHD_LOGGER_INFO("E300") << boost::format("ctrl 0x%x") % addrs.ctrl ;          const uint32_t sig = zf_peek32(_addrs.ctrl + ARBITER_RD_SIG);          UHD_ASSERT_THROW((sig >> 16) == 0xACE0); @@ -341,7 +347,7 @@ public:      virtual ~e300_fifo_interface_impl(void)      {          delete _waiter; -        UHD_LOG << "cleanup: munmap" << std::endl; +        UHD_LOGGER_TRACE("E300")<< "cleanup: munmap" ;          ::munmap(_buff, _config.ctrl_length + _config.buff_length);          ::close(_fd);      } diff --git a/host/lib/usrp/e300/e300_impl.cpp b/host/lib/usrp/e300/e300_impl.cpp index 84f50c67b..4b73ceac7 100644 --- a/host/lib/usrp/e300/e300_impl.cpp +++ b/host/lib/usrp/e300/e300_impl.cpp @@ -25,7 +25,7 @@  #include "e300_common.hpp"  #include "e300_remote_codec_ctrl.hpp" -#include <uhd/utils/msg.hpp> +  #include <uhd/utils/log.hpp>  #include <uhd/utils/static.hpp>  #include <uhd/utils/paths.hpp> @@ -75,11 +75,11 @@ static std::vector<std::string> discover_ip_addrs(      try {          udp_bcast_xport = uhd::transport::udp_simple::make_broadcast(addr_hint, port);      } catch(const std::exception &e) { -        UHD_MSG(error) << boost::format("Cannot open UDP transport on %s for discovery\n%s") -        % addr_hint % e.what() << std::endl; +        UHD_LOGGER_ERROR("E300") << boost::format("Cannot open UDP transport on %s for discovery%s") +        % addr_hint % e.what() ;          return addrs;      } catch(...) { -        UHD_MSG(error) << "E300 Network discovery unknown error" << std::endl; +        UHD_LOGGER_ERROR("E300") << "E300 Network discovery unknown error";          return addrs;      } @@ -95,10 +95,10 @@ static std::vector<std::string> discover_ip_addrs(      try {      udp_bcast_xport->send(boost::asio::buffer(&req, sizeof(req)));      } catch (const std::exception &ex) { -        UHD_MSG(error) << "E300 Network discovery error " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("E300") << "E300 Network discovery error " << ex.what();          return addrs;      } catch(...) { -        UHD_MSG(error) << "E300 Network discovery unknown error" << std::endl; +        UHD_LOGGER_ERROR("E300") << "E300 Network discovery unknown error";          return addrs;      } @@ -130,7 +130,7 @@ device_addrs_t e300_find(const device_addr_t &multi_dev_hint)      if (hints.size() > 1) {          device_addrs_t found_devices;          std::string err_msg; -        BOOST_FOREACH(const device_addr_t &hint_i, hints) +        for(const device_addr_t &hint_i:  hints)          {              device_addrs_t found_devices_i = e300_find(hint_i);              if(found_devices_i.size() != 1) @@ -165,7 +165,7 @@ device_addrs_t e300_find(const device_addr_t &multi_dev_hint)      if (not loopback_only) {          // if no address or node has been specified, send a broadcast          if ((not hint.has_key("addr")) and (not hint.has_key("node"))) { -            BOOST_FOREACH(const if_addrs_t &if_addrs, get_if_addrs()) +            for(const if_addrs_t &if_addrs:  get_if_addrs())              {                  // avoid the loopback device                  if (is_loopback(if_addrs)) @@ -187,7 +187,7 @@ device_addrs_t e300_find(const device_addr_t &multi_dev_hint)          std::vector<std::string> ip_addrs = discover_ip_addrs(              hint["addr"], E300_SERVER_I2C_PORT); -        BOOST_FOREACH(const std::string &ip_addr, ip_addrs) +        for(const std::string &ip_addr:  ip_addrs)          {              device_addr_t new_addr;              new_addr["type"] = "e3x0"; @@ -260,7 +260,7 @@ device_addrs_t e300_find(const device_addr_t &multi_dev_hint)   **********************************************************************/  static device::sptr e300_make(const device_addr_t &device_addr)  { -    UHD_LOG << "e300_make with args " << device_addr.to_pp_string() << std::endl; +    UHD_LOGGER_DEBUG("E300")<< "e300_make with args " << device_addr.to_pp_string() ;      if(device_addr.has_key("server"))          throw uhd::runtime_error(              str(boost::format("Please run the server executable \"%s\"") @@ -295,8 +295,8 @@ void get_e3x0_fpga_images(const uhd::device_addr_t &device_addr,          break;      case e300_eeprom_manager::UNKNOWN:      default: -        UHD_MSG(warning) << "Unknown motherboard type, loading e300 image." -                             << std::endl; +        UHD_LOGGER_WARNING("E300") << "Unknown motherboard type, loading e300 image." +                             ;          fpga_image = device_addr.cast<std::string>("fpga",              find_image_path(E300_FPGA_FILE_NAME));          idle_image = find_image_path(E3XX_SG1_FPGA_IDLE_FILE_NAME); @@ -405,14 +405,14 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr)      _codec_mgr = ad936x_manager::make(_codec_ctrl, fpga::NUM_RADIOS);  #ifdef E300_GPSD -    UHD_MSG(status) << "Detecting internal GPSDO " << std::flush; +    UHD_LOGGER_INFO("E300") << "Detecting internal GPSDO ";      try {          if (_xport_path == AXI)              _gps = gpsd_iface::make("localhost", 2947);          else              _gps = gpsd_iface::make(device_addr["addr"], 2947);      } catch (std::exception &e) { -        UHD_MSG(error) << "An error occured making GPSDd interface: " << e.what() << std::endl; +        UHD_LOGGER_ERROR("E300") << "An error occured making GPSDd interface: " << e.what();      }      if (_gps) { @@ -426,12 +426,12 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr)                  break;              }          } -        UHD_MSG(status) << (_gps->gps_detected() ? "found" : "not found") << std::endl; +        UHD_LOGGER_INFO("E300") << "GPSDO " << (_gps->gps_detected() ? "found" : "not found");      }  #endif      // Verify we can talk to the e300 core control registers ... -    UHD_MSG(status) << "Initializing core control..." << std::endl; +    UHD_LOGGER_INFO("E300") << "Initializing core control...";      this->_register_loopback_self_test(_global_regs);      // Verify fpga compatibility version matches at least for the major @@ -468,14 +468,14 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr)      // and do the misc mboard sensors      ////////////////////////////////////////////////////////////////////      _tree->create<int>(mb_path / "sensors"); -    BOOST_FOREACH(const std::string &name, _sensor_manager->get_sensors()) +    for(const std::string &name:  _sensor_manager->get_sensors())      {          _tree->create<sensor_value_t>(mb_path / "sensors" / name)              .set_publisher(boost::bind(&e300_sensor_manager::get_sensor, _sensor_manager, name));      }  #ifdef E300_GPSD      if (_gps) { -        BOOST_FOREACH(const std::string &name, _gps->get_sensors()) +        for(const std::string &name:  _gps->get_sensors())          {              _tree->create<sensor_value_t>(mb_path / "sensors" / name)                  .set_publisher(boost::bind(&gpsd_iface::get_sensor, _gps, name)); @@ -511,7 +511,7 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr)          this->_setup_radio(instance);      //now test each radio module's connection to the codec interface -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          _codec_mgr->loopback_self_test(              boost::bind( @@ -524,7 +524,7 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr)      // internal gpios      ////////////////////////////////////////////////////////////////////      gpio_atr_3000::sptr fp_gpio = gpio_atr_3000::make(_radio_perifs[0].ctrl, radio::sr_addr(radio::FP_GPIO), radio::RB32_FP_GPIO); -    BOOST_FOREACH(const gpio_attr_map_t::value_type attr, gpio_attr_map) +    for(const gpio_attr_map_t::value_type attr:  gpio_attr_map)      {          _tree->create<uint32_t>(mb_path / "gpio" / "INT0" / attr.second)              .add_coerced_subscriber(boost::bind(&gpio_atr_3000::set_gpio_attr, fp_gpio, attr.first, _1)) @@ -625,11 +625,11 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr)      // subdev spec contains full width of selections      subdev_spec_t rx_spec, tx_spec; -    BOOST_FOREACH(const std::string &fe, _tree->list(mb_path / "dboards" / "A" / "rx_frontends")) +    for(const std::string &fe:  _tree->list(mb_path / "dboards" / "A" / "rx_frontends"))      {          rx_spec.push_back(subdev_spec_pair_t("A", fe));      } -    BOOST_FOREACH(const std::string &fe, _tree->list(mb_path / "dboards" / "A" / "tx_frontends")) +    for(const std::string &fe:  _tree->list(mb_path / "dboards" / "A" / "tx_frontends"))      {          tx_spec.push_back(subdev_spec_pair_t("A", fe));      } @@ -692,11 +692,11 @@ void e300_impl::_enforce_tick_rate_limits(  double e300_impl::_set_tick_rate(const double rate)  { -    UHD_MSG(status) << "Asking for clock rate " << rate/1e6 << " MHz\n"; +    UHD_LOGGER_INFO("E300") << "Asking for clock rate " << rate/1e6 << " MHz\n";      _tick_rate = _codec_ctrl->set_clock_rate(rate); -    UHD_MSG(status) << "Actually got clock rate " << _tick_rate/1e6 << " MHz\n"; +    UHD_LOGGER_INFO("E300") << "Actually got clock rate " << _tick_rate/1e6 << " MHz\n"; -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          perif.time64->set_tick_rate(_tick_rate);          perif.time64->self_test(); @@ -707,7 +707,7 @@ double e300_impl::_set_tick_rate(const double rate)  void e300_impl::_register_loopback_self_test(wb_iface::sptr iface)  {      bool test_fail = false; -    UHD_MSG(status) << "Performing register loopback test... " << std::flush; +    UHD_LOGGER_INFO("E300") << "Performing register loopback test... ";      size_t hash = size_t(time(NULL));      for (size_t i = 0; i < 100; i++)      { @@ -716,7 +716,7 @@ void e300_impl::_register_loopback_self_test(wb_iface::sptr iface)          test_fail = iface->peek32(radio::RB32_TEST) != uint32_t(hash);          if (test_fail) break; //exit loop on any failure      } -    UHD_MSG(status) << ((test_fail)? " fail" : "pass") << std::endl; +    UHD_LOGGER_INFO("E300") << "Register loopback test " << ((test_fail)? " failed" : "passed");  }  uint32_t e300_impl::_get_version(compat_t which) @@ -747,19 +747,20 @@ uint32_t e300_impl::_allocate_sid(const sid_config_t &config)  {      const uint32_t stream = (config.dst_prefix | (config.router_dst_there << 2)) & 0xff; +    const size_t sid_framer = _sid_framer++; //increment for next setup      const uint32_t sid = 0          | (E300_DEVICE_HERE << 24) -        | (_sid_framer << 16) +        | (sid_framer << 16)          | (config.router_addr_there << 8)          | (stream << 0)      ; -    UHD_LOG << std::hex +    UHD_LOGGER_DEBUG("E300")<< std::hex          << " sid 0x" << sid -        << " framer 0x" << _sid_framer +        << " framer 0x" << sid_framer          << " stream 0x" << stream          << " router_dst_there 0x" << int(config.router_dst_there)          << " router_addr_there 0x" << int(config.router_addr_there) -        << std::dec << std::endl; +        << std::dec ;      // Program the E300 to recognize it's own local address.      _global_regs->poke32(global_regs::SR_CORE_XB_LOCAL, config.router_addr_there); @@ -775,26 +776,23 @@ uint32_t e300_impl::_allocate_sid(const sid_config_t &config)      _global_regs->poke32(XB_ADDR(E300_DEVICE_HERE),                           config.router_dst_here); -    UHD_LOG << std::hex +    UHD_LOGGER_TRACE("E300") << std::hex          << "done router config for sid 0x" << sid -        << std::dec << std::endl; - -    //increment for next setup -    _sid_framer++; +        << std::dec ;      return sid;  }  void e300_impl::_setup_dest_mapping(const uint32_t sid, const size_t which_stream)  { -    UHD_LOG << boost::format("Setting up dest map for 0x%lx to be stream %d") -                                     % (sid & 0xff) % which_stream << std::endl; +    UHD_LOGGER_DEBUG("E300") << boost::format("Setting up dest map for 0x%lx to be stream %d") +                                     % (sid & 0xff) % which_stream ;      _global_regs->poke32(DST_ADDR(sid & 0xff), which_stream);  }  void e300_impl::_update_time_source(const std::string &source)  { -    UHD_MSG(status) << boost::format("Setting time source to %s") % source << std::endl; +    UHD_LOGGER_INFO("E300") << boost::format("Setting time source to %s") % source;      if (source == "none" or source == "internal") {          _misc.pps_sel = global_regs::PPS_INT;  #ifdef E300_GPSD @@ -811,7 +809,7 @@ void e300_impl::_update_time_source(const std::string &source)  void e300_impl::_set_time(const uhd::time_spec_t& t)  { -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)          perif.time64->set_time_sync(t);      _misc.time_sync = 1;      _update_gpio_state(); @@ -1037,7 +1035,7 @@ void e300_impl::_setup_radio(const size_t dspno)      // create RF frontend interfacing      ////////////////////////////////////////////////////////////////////      static const std::vector<direction_t> dirs = boost::assign::list_of(RX_DIRECTION)(TX_DIRECTION); -    BOOST_FOREACH(direction_t dir, dirs) { +    for(direction_t dir:  dirs) {          const std::string x = (dir == RX_DIRECTION) ? "rx" : "tx";          const std::string key = boost::to_upper_copy(x) + std::string(((dspno == FE0)? "1" : "2"));          const fs_path rf_fe_path diff --git a/host/lib/usrp/e300/e300_impl.hpp b/host/lib/usrp/e300/e300_impl.hpp index 50d78fdd4..cc2e39e23 100644 --- a/host/lib/usrp/e300/e300_impl.hpp +++ b/host/lib/usrp/e300/e300_impl.hpp @@ -47,6 +47,7 @@  #include "e300_i2c.hpp"  #include "e300_eeprom_manager.hpp"  #include "e300_sensor_manager.hpp" +#include <atomic>  /* if we don't compile with gpsd support, don't bother */  #ifdef E300_GPSD @@ -288,7 +289,7 @@ private: // members      uhd::device_addr_t                     _device_addr;      xport_t                                _xport_path;      e300_fifo_interface::sptr              _fifo_iface; -    size_t                                 _sid_framer; +    std::atomic<size_t>                    _sid_framer;      radio_perifs_t                         _radio_perifs[2];      double                                 _tick_rate;      ad9361_ctrl::sptr                      _codec_ctrl; diff --git a/host/lib/usrp/e300/e300_io_impl.cpp b/host/lib/usrp/e300/e300_io_impl.cpp index 2514b7f40..4490afa21 100644 --- a/host/lib/usrp/e300/e300_io_impl.cpp +++ b/host/lib/usrp/e300/e300_io_impl.cpp @@ -26,7 +26,6 @@  #include <boost/bind.hpp>  #include <uhd/utils/tasks.hpp>  #include <uhd/utils/log.hpp> -#include <boost/foreach.hpp>  #include <boost/make_shared.hpp>  using namespace uhd; @@ -43,7 +42,7 @@ static const uint32_t HW_SEQ_NUM_MASK = 0xfff;  void e300_impl::_check_tick_rate_with_current_streamers(const double rate)  {      size_t max_tx_chan_count = 0, max_rx_chan_count = 0; -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          {              boost::shared_ptr<sph::recv_packet_streamer> rx_streamer = @@ -73,7 +72,7 @@ void e300_impl::_update_tick_rate(const double rate)  {      _check_tick_rate_with_current_streamers(rate); -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          boost::shared_ptr<sph::recv_packet_streamer> my_streamer =              boost::dynamic_pointer_cast<sph::recv_packet_streamer>(perif.rx_streamer.lock()); @@ -81,7 +80,7 @@ void e300_impl::_update_tick_rate(const double rate)              my_streamer->set_tick_rate(rate);          perif.framer->set_tick_rate(_tick_rate);      } -    BOOST_FOREACH(radio_perifs_t &perif, _radio_perifs) +    for(radio_perifs_t &perif:  _radio_perifs)      {          boost::shared_ptr<sph::send_packet_streamer> my_streamer =              boost::dynamic_pointer_cast<sph::send_packet_streamer>(perif.tx_streamer.lock()); @@ -336,7 +335,7 @@ static void handle_tx_async_msgs(boost::shared_ptr<e300_tx_fc_cache_t> fc_cache,      }      catch(const std::exception &ex)      { -        UHD_MSG(error) << "Error parsing async message packet: " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("E300") << "Error parsing async message packet: " << ex.what() ;          return;      } @@ -483,9 +482,9 @@ rx_streamer::sptr e300_impl::get_rx_stream(const uhd::stream_args_t &args_)              E300_RX_SW_BUFF_FULLNESS);          const size_t fc_handle_window = std::max<size_t>(1, fc_window / E300_RX_FC_REQUEST_FREQ); -        UHD_LOG << "RX Flow Control Window = " << fc_window +        UHD_LOGGER_DEBUG("E300") << "RX Flow Control Window = " << fc_window                  << ", RX Flow Control Handler Window = " -                << fc_handle_window << std::endl; +                << fc_handle_window ;          perif.framer->configure_flow_control(fc_window);          boost::shared_ptr<e300_rx_fc_cache_t> fc_cache(new e300_rx_fc_cache_t()); @@ -591,9 +590,9 @@ tx_streamer::sptr e300_impl::get_tx_stream(const uhd::stream_args_t &args_)          const size_t fc_window = data_xports.send->get_num_send_frames();          const size_t fc_handle_window = std::max<size_t>(1, fc_window/E300_TX_FC_RESPONSE_FREQ); -        UHD_LOG << "TX Flow Control Window = " << fc_window +        UHD_LOGGER_DEBUG("E300") << "TX Flow Control Window = " << fc_window                  << ", TX Flow Control Handler Window = " -                << fc_handle_window << std::endl; +                << fc_handle_window ;          perif.deframer->configure_flow_control(0/*cycs off*/, fc_handle_window/*pkts*/);          boost::shared_ptr<e300_tx_fc_cache_t> fc_cache(new e300_tx_fc_cache_t()); diff --git a/host/lib/usrp/e300/e300_network.cpp b/host/lib/usrp/e300/e300_network.cpp index e68f2a54d..f3045eb2d 100644 --- a/host/lib/usrp/e300/e300_network.cpp +++ b/host/lib/usrp/e300/e300_network.cpp @@ -31,7 +31,7 @@  #include "e300_common.hpp"  #include "e300_remote_codec_ctrl.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/byteswap.hpp>  #include <uhd/utils/paths.hpp> @@ -88,7 +88,7 @@ static void e300_recv_tunnel(              //step 1 - get the buffer              managed_recv_buffer::sptr buff = recver->get_recv_buff();              if (not buff) continue; -            if (E300_NETWORK_DEBUG) UHD_MSG(status) << name << " got " << buff->size() << std::endl; +            if (E300_NETWORK_DEBUG) UHD_LOGGER_INFO("E300") << name << " got " << buff->size();              //step 1.5 -- update endpoint              { @@ -102,13 +102,13 @@ static void e300_recv_tunnel(      }      catch(const std::exception &ex)      { -        UHD_MSG(error) << "e300_recv_tunnel exit " << name << " " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_recv_tunnel exit " << name << " " << ex.what();      }      catch(...)      { -        UHD_MSG(error) << "e300_recv_tunnel exit " << name << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_recv_tunnel exit " << name ;      } -    UHD_MSG(status) << "e300_recv_tunnel exit " << name << std::endl; +    UHD_LOGGER_INFO("E300") << "e300_recv_tunnel exit " << name;      *running = false;  } @@ -136,7 +136,7 @@ static void e300_send_tunnel(              while (not wait_for_recv_ready(recver->native(), 100) and *running){}              if (not *running) break;              const size_t num_bytes = recver->receive_from(asio::buffer(buff->cast<void *>(), buff->size()), _rx_endpoint); -            if (E300_NETWORK_DEBUG) UHD_MSG(status) << name << " got " << num_bytes << std::endl; +            if (E300_NETWORK_DEBUG) UHD_LOGGER_INFO("E300") << name << " got " << num_bytes;              //step 2.5 -- update endpoint              { @@ -150,13 +150,13 @@ static void e300_send_tunnel(      }      catch(const std::exception &ex)      { -        UHD_MSG(error) << "e300_send_tunnel exit " << name << " " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_send_tunnel exit " << name << " " << ex.what() ;      }      catch(...)      { -        UHD_MSG(error) << "e300_send_tunnel exit " << name << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_send_tunnel exit " << name ;      } -    UHD_MSG(status) << "e300_send_tunnel exit " << name << std::endl; +    UHD_LOGGER_INFO("E300") << "e300_send_tunnel exit " << name;      *running = false;  } @@ -252,7 +252,7 @@ static void e300_codec_ctrl_tunnel(                  out->bw = _codec_ctrl->set_bw_filter(which_str, in->bw);                  break;              default: -                UHD_MSG(status) << "Got unknown request?!" << std::endl; +                UHD_LOGGER_INFO("E300") << "Got unknown request?!";                  //Zero out actions to fail this request on client                  out->action = uhd::htonx<uint32_t>(0);              } @@ -262,13 +262,13 @@ static void e300_codec_ctrl_tunnel(      }      catch(const std::exception &ex)      { -        UHD_MSG(error) << "e300_ctrl_tunnel exit " << name << " " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_ctrl_tunnel exit " << name << " " << ex.what() ;      }      catch(...)      { -        UHD_MSG(error) << "e300_ctrl_tunnel exit " << name << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_ctrl_tunnel exit " << name ;      } -    UHD_MSG(status) << "e300_ctrl_tunnel exit " << name << std::endl; +    UHD_LOGGER_INFO("E300") << "e300_ctrl_tunnel exit " << name;      *running = false;  } @@ -309,13 +309,13 @@ static void e300_global_regs_tunnel(      }      catch(const std::exception &ex)      { -        UHD_MSG(error) << "e300_gregs_tunnel exit " << name << " " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_gregs_tunnel exit " << name << " " << ex.what() ;      }      catch(...)      { -        UHD_MSG(error) << "e300_gregs_tunnel exit " << name << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_gregs_tunnel exit " << name ;      } -    UHD_MSG(status) << "e300_gregs_tunnel exit " << name << std::endl; +    UHD_LOGGER_INFO("E300") << "e300_gregs_tunnel exit " << name;      *running = false;  } @@ -353,20 +353,20 @@ static void e300_sensor_tunnel(                  in->value = uhd::htonx<uint32_t>(                      sensor_manager->get_ref_lock().to_bool() ? 1 : 0);              } else -                UHD_MSG(status) << "Got unknown request?!" << std::endl; +                UHD_LOGGER_INFO("E300") << "Got unknown request?!";              socket->send_to(asio::buffer(in_buff, sizeof(sensor_transaction_t)), *endpoint);          }      }      catch(const std::exception &ex)      { -        UHD_MSG(error) << "e300_sensor_tunnel exit " << name << " " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_sensor_tunnel exit " << name << " " << ex.what() ;      }      catch(...)      { -        UHD_MSG(error) << "e300_sensor_tunnel exit " << name << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_sensor_tunnel exit " << name ;      } -    UHD_MSG(status) << "e300_sensor_tunnel exit " << name << std::endl; +    UHD_LOGGER_INFO("E300") << "e300_sensor_tunnel exit " << name;      *running = false;  } @@ -419,19 +419,19 @@ static void e300_i2c_tunnel(                  }              } else { -                UHD_MSG(error) << "e300_i2c_tunnel could not handle message." << std::endl; +                UHD_LOGGER_ERROR("E300") << "e300_i2c_tunnel could not handle message." ;              }          }      }      catch(const std::exception &ex)      { -        UHD_MSG(error) << "e300_i2c_tunnel exit " << name << " " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_i2c_tunnel exit " << name << " " << ex.what() ;      }      catch(...)      { -        UHD_MSG(error) << "e300_i2c_tunnel exit " << name << std::endl; +        UHD_LOGGER_ERROR("E300") << "e300_i2c_tunnel exit " << name ;      } -    UHD_MSG(status) << "e300_i2c_tunnel exit " << name << std::endl; +    UHD_LOGGER_INFO("E300") << "e300_i2c_tunnel exit " << name;      *running = false;  } @@ -491,7 +491,7 @@ void network_server_impl::_run_server(      //boost::shared_ptr<asio::ip::udp::acceptor> acceptor(new asio::ip::udp::acceptor(io_service, endpoint));      while (not boost::this_thread::interruption_requested())      { -        UHD_MSG(status) << "e300 run server on port " << port << " for " << what << std::endl; +        UHD_LOGGER_INFO("E300") << "e300 run server on port " << port << " for " << what;          try          {              //while (not wait_for_recv_ready(acceptor->native(), 100)) @@ -501,7 +501,7 @@ void network_server_impl::_run_server(              boost::shared_ptr<asio::ip::udp::socket> socket;              socket.reset(new asio::ip::udp::socket(io_service, endpoint));              //acceptor->accept(*socket); -            UHD_MSG(status) << "e300 socket accept on port " << port << " for " << what << std::endl; +            UHD_LOGGER_INFO("E300") << "e300 socket accept on port " << port << " for " << what;              //asio::ip::udp::no_delay option(true);              //socket->set_option(option);              boost::thread_group tg; @@ -586,8 +586,8 @@ network_server_impl::network_server_impl(const uhd::device_addr_t &device_addr)                  break;              case e300_eeprom_manager::UNKNOWN:              default: -                UHD_MSG(warning) << "Unknown motherboard type, loading e300 image." -                                 << std::endl; +                UHD_LOGGER_WARNING("E300") << "Unknown motherboard type, loading e300 image." +                                 ;                  fpga_image = find_image_path(E300_FPGA_FILE_NAME);                  break;              } diff --git a/host/lib/usrp/e300/e300_remote_codec_ctrl.cpp b/host/lib/usrp/e300/e300_remote_codec_ctrl.cpp index b7c46c17d..d970d7221 100644 --- a/host/lib/usrp/e300/e300_remote_codec_ctrl.cpp +++ b/host/lib/usrp/e300/e300_remote_codec_ctrl.cpp @@ -242,7 +242,7 @@ public:      //! Write back a filter      void set_filter(const std::string &, const std::string &, const filter_info_base::sptr)      { -        UHD_MSG(warning) << "Attempting to set filter on E300 in network mode." << std::endl; +        UHD_LOGGER_WARNING("E300") << "Attempting to set filter on E300 in network mode." ;      }      void output_digital_test_tone(UHD_UNUSED(bool enb)) diff --git a/host/lib/usrp/e300/e300_sysfs_hooks.cpp b/host/lib/usrp/e300/e300_sysfs_hooks.cpp index 7bd1d6d7e..bcfca8b92 100644 --- a/host/lib/usrp/e300/e300_sysfs_hooks.cpp +++ b/host/lib/usrp/e300/e300_sysfs_hooks.cpp @@ -32,7 +32,7 @@  #include <boost/format.hpp>  #include <boost/lexical_cast.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/exception.hpp>  static const std::string E300_AXI_FPGA_SYSFS = "40000000.axi-fpga"; diff --git a/host/lib/usrp/gps_ctrl.cpp b/host/lib/usrp/gps_ctrl.cpp index 447a13c33..a5d1748fe 100644 --- a/host/lib/usrp/gps_ctrl.cpp +++ b/host/lib/usrp/gps_ctrl.cpp @@ -16,25 +16,25 @@  //  #include <uhd/usrp/gps_ctrl.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/utils/log.hpp>  #include <uhd/exception.hpp>  #include <uhd/types/sensors.hpp>  #include <boost/algorithm/string.hpp>  #include <boost/assign/list_of.hpp>  #include <stdint.h> -#include <boost/date_time/posix_time/posix_time.hpp>  #include <boost/thread/thread.hpp>  #include <boost/tokenizer.hpp>  #include <boost/format.hpp>  #include <boost/regex.hpp>  #include <boost/thread/mutex.hpp> +#include <ctime> +#include <string> +#include <boost/date_time.hpp>  #include "boost/tuple/tuple.hpp" -#include "boost/foreach.hpp"  using namespace uhd; -using namespace boost::gregorian;  using namespace boost::posix_time;  using namespace boost::algorithm;  using namespace boost::this_thread; @@ -92,7 +92,7 @@ private:                      sentences[which].get<2>() = true;                  }              } catch(std::exception &e) { -                UHD_LOGV(often) << "get_sentence: " << e.what(); +                UHD_LOGGER_DEBUG("GPS") << "get_sentence: " << e.what();              }              if (not sentence.empty() or now > exit_time) @@ -159,7 +159,7 @@ private:          if (msg.length() < 6)          { -            UHD_LOGV(regularly) << __FUNCTION__ << ": Short GPSDO string: " << msg << std::endl; +            UHD_LOGGER_WARNING("GPS") << __FUNCTION__ << ": Short GPSDO string: " << msg ;              continue;          } @@ -174,14 +174,14 @@ private:          }          else          { -            UHD_LOGV(regularly) << __FUNCTION__ << ": Malformed GPSDO string: " << msg << std::endl; +            UHD_LOGGER_WARNING("GPS") << __FUNCTION__ << ": Malformed GPSDO string: " << msg ;          }      }      boost::system_time time = boost::get_system_time();      // Update sentences with newly read data -    BOOST_FOREACH(std::string key, keys) +    for(std::string key:  keys)      {          if (not msgs[key].empty())          { @@ -234,7 +234,7 @@ public:          if(i_heard_some_nmea) {              _gps_type = GPS_TYPE_GENERIC_NMEA;          } else if(i_heard_something_weird) { -            UHD_MSG(error) << "GPS invalid reply \"" << reply << "\", assuming none available" << std::endl; +            UHD_LOGGER_ERROR("GPS") << "GPS invalid reply \"" << reply << "\", assuming none available";          }      } @@ -242,17 +242,17 @@ public:      case GPS_TYPE_INTERNAL_GPSDO:        erase_all(reply, "\r");        erase_all(reply, "\n"); -      UHD_MSG(status) << "Found an internal GPSDO: " << reply << std::endl; +      UHD_LOGGER_INFO("GPS") << "Found an internal GPSDO: " << reply;        init_gpsdo();        break;      case GPS_TYPE_GENERIC_NMEA: -      UHD_MSG(status) << "Found a generic NMEA GPS device" << std::endl; +        UHD_LOGGER_INFO("GPS") << "Found a generic NMEA GPS device";        break;      case GPS_TYPE_NONE:      default: -      UHD_MSG(status) << "No GPSDO found" << std::endl; +        UHD_LOGGER_INFO("GPS") << "No GPSDO found";        break;      } @@ -349,20 +349,20 @@ private:                  throw uhd::value_error(str(boost::format("Invalid response \"%s\"") % reply));              } -            //just trust me on this one -            gps_time = ptime( date( -                             greg_year(boost::lexical_cast<int>(datestr.substr(4, 2)) + 2000), -                             greg_month(boost::lexical_cast<int>(datestr.substr(2, 2))), -                             greg_day(boost::lexical_cast<int>(datestr.substr(0, 2))) -                           ), -                          hours(  boost::lexical_cast<int>(timestr.substr(0, 2))) -                        + minutes(boost::lexical_cast<int>(timestr.substr(2, 2))) -                        + seconds(boost::lexical_cast<int>(timestr.substr(4, 2))) -                     ); +            struct tm raw_date; +            raw_date.tm_year = std::stoi(datestr.substr(4, 2)) + 2000 - 1900; // years since 1900 +            raw_date.tm_mon = std::stoi(datestr.substr(2, 2)) - 1; // months since january (0-11) +            raw_date.tm_mday = std::stoi(datestr.substr(0, 2)); // dom (1-31) +            raw_date.tm_hour = std::stoi(timestr.substr(0, 2)); +            raw_date.tm_min = std::stoi(timestr.substr(2, 2)); +            raw_date.tm_sec = std::stoi(timestr.substr(4,2)); +            gps_time = boost::posix_time::ptime_from_tm(raw_date); + +            UHD_LOG_TRACE("GPS", "GPS time: " + boost::posix_time::to_simple_string(gps_time));              return gps_time;          } catch(std::exception &e) { -            UHD_LOGV(often) << "get_time: " << e.what(); +            UHD_LOGGER_DEBUG("GPS") << "get_time: " << e.what();              error_cnt++;          }      } @@ -389,7 +389,7 @@ private:              else                  return (get_token(reply, 6) != "0");          } catch(std::exception &e) { -            UHD_LOGV(often) << "locked: " << e.what(); +            UHD_LOGGER_DEBUG("GPS") << "locked: " << e.what();              error_cnt++;          }      } diff --git a/host/lib/usrp/gpsd_iface.cpp b/host/lib/usrp/gpsd_iface.cpp index 98b359135..c5d4a1745 100644 --- a/host/lib/usrp/gpsd_iface.cpp +++ b/host/lib/usrp/gpsd_iface.cpp @@ -31,7 +31,7 @@  #include <uhd/exception.hpp>  #include <uhd/usrp/gps_ctrl.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/types/dict.hpp>  #include "gpsd_iface.hpp" diff --git a/host/lib/usrp/mboard_eeprom.cpp b/host/lib/usrp/mboard_eeprom.cpp index 4cf58cd05..ecae5e56d 100644 --- a/host/lib/usrp/mboard_eeprom.cpp +++ b/host/lib/usrp/mboard_eeprom.cpp @@ -22,7 +22,6 @@  #include <boost/asio/ip/address_v4.hpp>  #include <boost/assign/list_of.hpp>  #include <boost/lexical_cast.hpp> -#include <boost/foreach.hpp>  #include <algorithm>  #include <iostream>  #include <cstddef> @@ -600,7 +599,7 @@ template <typename T> static const byte_vector_t to_bytes(const T &item){  }  #define sizeof_member(struct_name, member_name) \ -    sizeof(reinterpret_cast<struct_name*>(NULL)->member_name) +    sizeof(reinterpret_cast<struct_name*>(0)->member_name)  static void load_e100(mboard_eeprom_t &mb_eeprom, i2c_iface &iface){      const size_t num_bytes = offsetof(e100_eeprom_map, model); diff --git a/host/lib/usrp/multi_usrp.cpp b/host/lib/usrp/multi_usrp.cpp index ac0f52255..0910ad59d 100644 --- a/host/lib/usrp/multi_usrp.cpp +++ b/host/lib/usrp/multi_usrp.cpp @@ -17,7 +17,7 @@  #include <uhd/property_tree.hpp>  #include <uhd/usrp/multi_usrp.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/exception.hpp>  #include <uhd/utils/log.hpp>  #include <uhd/utils/math.hpp> @@ -30,7 +30,6 @@  #include "legacy_compat.hpp"  #include <boost/assign/list_of.hpp>  #include <boost/thread.hpp> -#include <boost/foreach.hpp>  #include <boost/format.hpp>  #include <boost/algorithm/string.hpp>  #include <algorithm> @@ -66,7 +65,7 @@ static void do_samp_rate_warning_message(  ){      static const double max_allowed_error = 1.0; //Sps      if (std::abs(target_rate - actual_rate) > max_allowed_error){ -        UHD_MSG(warning) << boost::format( +        UHD_LOGGER_WARNING("MULTI_USRP") << boost::format(              "The hardware does not support the requested %s sample rate:\n"              "Target sample rate: %f MSps\n"              "Actual sample rate: %f MSps\n" @@ -97,7 +96,7 @@ static void do_samp_rate_warning_message(      if(requested_freq_success and target_freq_success and rf_lo_tune_success              and dsp_tune_success) { -        UHD_MSG(status) << boost::format( +        UHD_LOGGER_INFO("MULTI_USRP") << boost::format(                  "Successfully tuned to %f MHz\n\n")                  % (actual_freq / 1e6);      } else { @@ -120,7 +119,7 @@ static void do_samp_rate_warning_message(              results_string += rf_lo_message.str(); -            UHD_MSG(status) << results_string; +            UHD_LOGGER_INFO("MULTI_USRP") << results_string;              return;          } @@ -174,7 +173,7 @@ static void do_samp_rate_warning_message(              results_string += failure_message.str();          } -        UHD_MSG(warning) << results_string << std::endl; +        UHD_LOGGER_WARNING("MULTI_USRP") << results_string ;      }  }*/ @@ -190,7 +189,7 @@ static meta_range_t make_overall_tune_range(      const double bw  ){      meta_range_t range; -    BOOST_FOREACH(const range_t &sub_range, fe_range){ +    for(const range_t &sub_range:  fe_range){          range.push_back(range_t(              sub_range.start() + std::max(dsp_range.start(), -bw/2),              sub_range.stop() + std::min(dsp_range.stop(), bw/2), @@ -262,7 +261,8 @@ static tune_result_t tune_xx_subdev_and_dsp(       * tune_request. This lo_offset is based on the requirements of the FE, and       * does not reflect a user-requested lo_offset, which is handled later. */      double lo_offset = 0.0; -    if (rf_fe_subtree->access<bool>("use_lo_offset").get()){ +    if (rf_fe_subtree->exists("use_lo_offset") and +        rf_fe_subtree->access<bool>("use_lo_offset").get()){          // If the frontend has lo_offset value and range properties, trust it          // for lo_offset          if (rf_fe_subtree->exists("lo_offset/value")) { @@ -459,7 +459,7 @@ public:              if (_tree->exists(mb_root(mboard) / "auto_tick_rate")                      and _tree->access<bool>(mb_root(mboard) / "auto_tick_rate").get()) {                  _tree->access<bool>(mb_root(mboard) / "auto_tick_rate").set(false); -                UHD_MSG(status) << "Setting master clock rate selection to 'manual'." << std::endl; +                UHD_LOGGER_INFO("MULTI_USRP") << "Setting master clock rate selection to 'manual'.";              }              _tree->access<double>(mb_root(mboard) / "tick_rate").set(rate);              return; @@ -557,7 +557,7 @@ public:      }      void set_time_unknown_pps(const time_spec_t &time_spec){ -        UHD_MSG(status) << "    1) catch time transition at pps edge" << std::endl; +        UHD_LOGGER_INFO("MULTI_USRP") << "    1) catch time transition at pps edge";          boost::system_time end_time = boost::get_system_time() + boost::posix_time::milliseconds(1100);          time_spec_t time_start_last_pps = get_time_last_pps();          while (time_start_last_pps == get_time_last_pps()) @@ -573,7 +573,7 @@ public:              boost::this_thread::sleep(boost::posix_time::milliseconds(1));          } -        UHD_MSG(status) << "    2) set times next pps (synchronously)" << std::endl; +        UHD_LOGGER_INFO("MULTI_USRP") << "    2) set times next pps (synchronously)";          set_time_next_pps(time_spec, ALL_MBOARDS);          boost::this_thread::sleep(boost::posix_time::seconds(1)); @@ -582,7 +582,7 @@ public:              time_spec_t time_0 = this->get_time_now(0);              time_spec_t time_i = this->get_time_now(m);              if (time_i < time_0 or (time_i - time_0) > time_spec_t(0.01)){ //10 ms: greater than RTT but not too big -                UHD_MSG(warning) << boost::format( +                UHD_LOGGER_WARNING("MULTI_USRP") << boost::format(                      "Detected time deviation between board %d and board 0.\n"                      "Board 0 time is %f seconds.\n"                      "Board %d time is %f seconds.\n" @@ -797,7 +797,7 @@ public:              {                  throw uhd::index_error(str(boost::format("multi_usrp::get_rx_subdev_spec(%u) failed to make default spec - %s") % mboard % e.what()));              } -            UHD_MSG(status) << "Selecting default RX front end spec: " << spec.to_pp_string() << std::endl; +            UHD_LOGGER_INFO("MULTI_USRP") << "Selecting default RX front end spec: " << spec.to_pp_string();          }          return spec;      } @@ -873,7 +873,7 @@ public:      std::vector<std::string> get_rx_lo_names(size_t chan = 0){          std::vector<std::string> lo_names;          if (_tree->exists(rx_rf_fe_root(chan) / "los")) { -            BOOST_FOREACH(const std::string &name, _tree->list(rx_rf_fe_root(chan) / "los")) { +            for(const std::string &name:  _tree->list(rx_rf_fe_root(chan) / "los")) {                  lo_names.push_back(name);              }          } @@ -887,7 +887,7 @@ public:                      //Special value ALL_LOS support atomically sets the source for all LOs                      _tree->access<std::string>(rx_rf_fe_root(chan) / "los" / ALL_LOS / "source" / "value").set(src);                  } else { -                    BOOST_FOREACH(const std::string &n, _tree->list(rx_rf_fe_root(chan) / "los")) { +                    for(const std::string &n:  _tree->list(rx_rf_fe_root(chan) / "los")) {                          this->set_rx_lo_source(src, n, chan);                      }                  } @@ -950,7 +950,7 @@ public:                      //Special value ALL_LOS support atomically sets the source for all LOs                      _tree->access<bool>(rx_rf_fe_root(chan) / "los" / ALL_LOS / "export").set(enabled);                  } else { -                    BOOST_FOREACH(const std::string &n, _tree->list(rx_rf_fe_root(chan) / "los")) { +                    for(const std::string &n:  _tree->list(rx_rf_fe_root(chan) / "los")) {                          this->set_rx_lo_export_enabled(enabled, n, chan);                      }                  } @@ -1041,7 +1041,7 @@ public:              if (_tree->exists(rx_rf_fe_root(chan) / "gain" / "agc")) {                  bool agc = _tree->access<bool>(rx_rf_fe_root(chan) / "gain" / "agc" / "enable").get();                  if(agc) { -                    UHD_MSG(warning) << "AGC enabled for this channel. Setting will be ignored." << std::endl; +                    UHD_LOGGER_WARNING("MULTI_USRP") << "AGC enabled for this channel. Setting will be ignored." ;                  }              }          } else { @@ -1049,7 +1049,7 @@ public:                  if (_tree->exists(rx_rf_fe_root(c) / "gain" / "agc")) {                      bool agc = _tree->access<bool>(rx_rf_fe_root(chan) / "gain" / "agc" / "enable").get();                      if(agc) { -                        UHD_MSG(warning) << "AGC enabled for this channel. Setting will be ignored." << std::endl; +                        UHD_LOGGER_WARNING("MULTI_USRP") << "AGC enabled for this channel. Setting will be ignored." ;                      }                  }              } @@ -1079,7 +1079,7 @@ public:              if (_tree->exists(rx_rf_fe_root(chan) / "gain" / "agc" / "enable")) {                  _tree->access<bool>(rx_rf_fe_root(chan) / "gain" / "agc" / "enable").set(enable);              } else { -                UHD_MSG(warning) << "AGC is not available on this device." << std::endl; +                UHD_LOGGER_WARNING("MULTI_USRP") << "AGC is not available on this device." ;              }              return;          } @@ -1157,7 +1157,11 @@ public:      }      std::vector<std::string> get_rx_sensor_names(size_t chan){ -        return _tree->list(rx_rf_fe_root(chan) / "sensors"); +        std::vector<std::string> sensor_names; +        if (_tree->exists(rx_rf_fe_root(chan) / "sensors")) { +            sensor_names = _tree->list(rx_rf_fe_root(chan) / "sensors"); +        } +        return sensor_names;      }      void set_rx_dc_offset(const bool enb, size_t chan){ @@ -1168,7 +1172,7 @@ public:                  /*For B2xx devices the dc-offset correction is implemented in the rf front-end*/                  _tree->access<bool>(rx_rf_fe_root(chan) / "dc_offset" / "enable").set(enb);              } else { -                UHD_MSG(warning) << "Setting DC offset compensation is not possible on this device." << std::endl; +                UHD_LOGGER_WARNING("MULTI_USRP") << "Setting DC offset compensation is not possible on this device." ;              }              return;          } @@ -1182,7 +1186,7 @@ public:              if (_tree->exists(rx_fe_root(chan) / "dc_offset" / "value")) {                  _tree->access<std::complex<double> >(rx_fe_root(chan) / "dc_offset" / "value").set(offset);              } else { -                UHD_MSG(warning) << "Setting DC offset is not possible on this device." << std::endl; +                UHD_LOGGER_WARNING("MULTI_USRP") << "Setting DC offset is not possible on this device." ;              }              return;          } @@ -1196,7 +1200,7 @@ public:              if (_tree->exists(rx_rf_fe_root(chan) / "iq_balance" / "enable")) {                  _tree->access<bool>(rx_rf_fe_root(chan) / "iq_balance" / "enable").set(enb);              } else { -                UHD_MSG(warning) << "Setting IQ imbalance compensation is not possible on this device." << std::endl; +                UHD_LOGGER_WARNING("MULTI_USRP") << "Setting IQ imbalance compensation is not possible on this device." ;              }              return;          } @@ -1210,7 +1214,7 @@ public:              if (_tree->exists(rx_fe_root(chan) / "iq_balance" / "value")) {                  _tree->access<std::complex<double> >(rx_fe_root(chan) / "iq_balance" / "value").set(offset);              } else { -                UHD_MSG(warning) << "Setting IQ balance is not possible on this device." << std::endl; +                UHD_LOGGER_WARNING("MULTI_USRP") << "Setting IQ balance is not possible on this device." ;              }              return;          } @@ -1337,7 +1341,7 @@ public:              {                  throw uhd::index_error(str(boost::format("multi_usrp::get_tx_subdev_spec(%u) failed to make default spec - %s") % mboard % e.what()));              } -            UHD_MSG(status) << "Selecting default TX front end spec: " << spec.to_pp_string() << std::endl; +            UHD_LOGGER_INFO("MULTI_USRP") << "Selecting default TX front end spec: " << spec.to_pp_string();          }          return spec;      } @@ -1497,7 +1501,11 @@ public:      }      std::vector<std::string> get_tx_sensor_names(size_t chan){ -        return _tree->list(tx_rf_fe_root(chan) / "sensors"); +        std::vector<std::string> sensor_names; +        if (_tree->exists(rx_rf_fe_root(chan) / "sensors")) { +            sensor_names = _tree->list(tx_rf_fe_root(chan) / "sensors"); +        } +        return sensor_names;      }      void set_tx_dc_offset(const std::complex<double> &offset, size_t chan){ @@ -1505,7 +1513,7 @@ public:              if (_tree->exists(tx_fe_root(chan) / "dc_offset" / "value")) {                  _tree->access<std::complex<double> >(tx_fe_root(chan) / "dc_offset" / "value").set(offset);              } else { -                UHD_MSG(warning) << "Setting DC offset is not possible on this device." << std::endl; +                UHD_LOGGER_WARNING("MULTI_USRP") << "Setting DC offset is not possible on this device." ;              }              return;          } @@ -1519,7 +1527,7 @@ public:              if (_tree->exists(tx_fe_root(chan) / "iq_balance" / "value")) {                  _tree->access<std::complex<double> >(tx_fe_root(chan) / "iq_balance" / "value").set(offset);              } else { -                UHD_MSG(warning) << "Setting IQ balance is not possible on this device." << std::endl; +                UHD_LOGGER_WARNING("MULTI_USRP") << "Setting IQ balance is not possible on this device." ;              }              return;          } @@ -1536,12 +1544,12 @@ public:          std::vector<std::string> banks;          if (_tree->exists(mb_root(mboard) / "gpio"))          { -            BOOST_FOREACH(const std::string &name, _tree->list(mb_root(mboard) / "gpio")) +            for(const std::string &name:  _tree->list(mb_root(mboard) / "gpio"))              {                  banks.push_back(name);              }          } -        BOOST_FOREACH(const std::string &name, _tree->list(mb_root(mboard) / "dboards")) +        for(const std::string &name:  _tree->list(mb_root(mboard) / "dboards"))          {              banks.push_back("RX"+name);              banks.push_back("TX"+name); @@ -1755,8 +1763,12 @@ private:      {          try          { -            const std::string name = _tree->list("/mboards").at(mboard); -            return "/mboards/" + name; +            const std::string tree_path = "/mboards/" + boost::lexical_cast<std::string>(mboard); +            if (_tree->exists(tree_path)) { +                return tree_path; +            } else { +                throw uhd::index_error(str(boost::format("multi_usrp::mb_root(%u) - path not found") % mboard)); +            }          }          catch(const std::exception &e)          { @@ -1779,8 +1791,12 @@ private:          try          { -            const std::string name = _tree->list(mb_root(mcp.mboard) / "rx_dsps").at(mcp.chan); -            return mb_root(mcp.mboard) / "rx_dsps" / name; +            const std::string tree_path = mb_root(mcp.mboard) / "rx_dsps" / boost::lexical_cast<std::string>(mcp.chan); +            if (_tree->exists(tree_path)) { +                return tree_path; +            } else { +                throw uhd::index_error(str(boost::format("multi_usrp::rx_dsp_root(%u) - mcp(%u) - path not found") % chan % mcp.chan)); +            }          }          catch(const std::exception &e)          { @@ -1802,8 +1818,12 @@ private:          }          try          { -            const std::string name = _tree->list(mb_root(mcp.mboard) / "tx_dsps").at(mcp.chan); -            return mb_root(mcp.mboard) / "tx_dsps" / name; +            const std::string tree_path = mb_root(mcp.mboard) / "tx_dsps" / boost::lexical_cast<std::string>(mcp.chan); +            if (_tree->exists(tree_path)) { +                return tree_path; +            } else { +                throw uhd::index_error(str(boost::format("multi_usrp::tx_dsp_root(%u) - mcp(%u) - path not found") % chan % mcp.chan)); +            }          }          catch(const std::exception &e)          { @@ -1877,10 +1897,10 @@ private:          mboard_chan_pair mcp = rx_chan_to_mcp(chan);          const subdev_spec_pair_t spec = get_rx_subdev_spec(mcp.mboard).at(mcp.chan);          gain_group::sptr gg = gain_group::make(); -        BOOST_FOREACH(const std::string &name, _tree->list(mb_root(mcp.mboard) / "rx_codecs" / spec.db_name / "gains")){ +        for(const std::string &name:  _tree->list(mb_root(mcp.mboard) / "rx_codecs" / spec.db_name / "gains")){              gg->register_fcns("ADC-"+name, make_gain_fcns_from_subtree(_tree->subtree(mb_root(mcp.mboard) / "rx_codecs" / spec.db_name / "gains" / name)), 0 /* low prio */);          } -        BOOST_FOREACH(const std::string &name, _tree->list(rx_rf_fe_root(chan) / "gains")){ +        for(const std::string &name:  _tree->list(rx_rf_fe_root(chan) / "gains")){              gg->register_fcns(name, make_gain_fcns_from_subtree(_tree->subtree(rx_rf_fe_root(chan) / "gains" / name)), 1 /* high prio */);          }          return gg; @@ -1890,10 +1910,10 @@ private:          mboard_chan_pair mcp = tx_chan_to_mcp(chan);          const subdev_spec_pair_t spec = get_tx_subdev_spec(mcp.mboard).at(mcp.chan);          gain_group::sptr gg = gain_group::make(); -        BOOST_FOREACH(const std::string &name, _tree->list(mb_root(mcp.mboard) / "tx_codecs" / spec.db_name / "gains")){ +        for(const std::string &name:  _tree->list(mb_root(mcp.mboard) / "tx_codecs" / spec.db_name / "gains")){              gg->register_fcns("DAC-"+name, make_gain_fcns_from_subtree(_tree->subtree(mb_root(mcp.mboard) / "tx_codecs" / spec.db_name / "gains" / name)), 1 /* high prio */);          } -        BOOST_FOREACH(const std::string &name, _tree->list(tx_rf_fe_root(chan) / "gains")){ +        for(const std::string &name:  _tree->list(tx_rf_fe_root(chan) / "gains")){              gg->register_fcns(name, make_gain_fcns_from_subtree(_tree->subtree(tx_rf_fe_root(chan) / "gains" / name)), 0 /* low prio */);          }          return gg; @@ -1907,7 +1927,7 @@ private:          size_t bytes_per_sample = convert::get_bytes_per_item(args.otw_format.empty() ? "sc16" : args.otw_format);          double max_link_rate = 0;          double sum_rate = 0; -        BOOST_FOREACH(const size_t chan, args.channels) { +        for(const size_t chan:  args.channels) {              mboard_chan_pair mcp = is_tx ? tx_chan_to_mcp(chan) : rx_chan_to_mcp(chan);              if (_tree->exists(mb_root(mcp.mboard) / "link_max_rate")) {                  max_link_rate = std::max( @@ -1919,10 +1939,10 @@ private:          }          sum_rate /= get_num_mboards();          if (max_link_rate > 0 and (max_link_rate / bytes_per_sample) < sum_rate) { -            UHD_MSG(warning) << boost::format( +            UHD_LOGGER_WARNING("MULTI_USRP") << boost::format(                  "The total sum of rates (%f MSps on %u channels) exceeds the maximum capacity of the connection.\n"                  "This can cause %s." -            ) % (sum_rate/1e6) % args.channels.size() % (is_tx ? "underruns (U)" : "overflows (O)")  << std::endl; +            ) % (sum_rate/1e6) % args.channels.size() % (is_tx ? "underruns (U)" : "overflows (O)")  ;              link_rate_is_ok = false;          } @@ -1938,6 +1958,6 @@ multi_usrp::~multi_usrp(void){   * The Make Function   **********************************************************************/  multi_usrp::sptr multi_usrp::make(const device_addr_t &dev_addr){ -    UHD_LOG << "multi_usrp::make with args " << dev_addr.to_pp_string() << std::endl; +    UHD_LOGGER_TRACE("MULTI_USRP") << "multi_usrp::make with args " << dev_addr.to_pp_string() ;      return sptr(new multi_usrp_impl(dev_addr));  } diff --git a/host/lib/usrp/n230/CMakeLists.txt b/host/lib/usrp/n230/CMakeLists.txt index 9eaccffba..8bed1f26d 100644 --- a/host/lib/usrp/n230/CMakeLists.txt +++ b/host/lib/usrp/n230/CMakeLists.txt @@ -33,5 +33,6 @@ IF(ENABLE_N230)          ${CMAKE_CURRENT_SOURCE_DIR}/n230_frontend_ctrl.cpp          ${CMAKE_CURRENT_SOURCE_DIR}/n230_uart.cpp          ${CMAKE_CURRENT_SOURCE_DIR}/n230_image_loader.cpp +        ${CMAKE_CURRENT_SOURCE_DIR}/n230_fw_ctrl_iface.cpp     )  ENDIF(ENABLE_N230) diff --git a/host/lib/usrp/n230/n230_clk_pps_ctrl.cpp b/host/lib/usrp/n230/n230_clk_pps_ctrl.cpp index 2bcfb0394..372325fbe 100644 --- a/host/lib/usrp/n230/n230_clk_pps_ctrl.cpp +++ b/host/lib/usrp/n230/n230_clk_pps_ctrl.cpp @@ -17,11 +17,10 @@  #include "n230_clk_pps_ctrl.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp>  #include <stdint.h>  #include <boost/format.hpp> -#include <boost/foreach.hpp>  #include <stdexcept>  #include <cmath>  #include <cstdlib> @@ -56,11 +55,11 @@ public:      double set_tick_rate(const double rate)      { -        UHD_MSG(status) << "Configuring a tick rate of " << rate/1e6 << " MHz... "; +        UHD_LOGGER_INFO("N230") << "Configuring a tick rate of " << rate/1e6 << " MHz... ";          _tick_rate = _codec_ctrl->set_clock_rate(rate); -        UHD_MSG(status) << "got " << _tick_rate/1e6 << " MHz\n"; +        UHD_LOGGER_INFO("N230") << "got " << _tick_rate/1e6 << " MHz\n"; -        BOOST_FOREACH(time_core_3000::sptr& time_core, _time_cores) { +        for(time_core_3000::sptr& time_core:  _time_cores) {              time_core->set_tick_rate(_tick_rate);              time_core->self_test();          } diff --git a/host/lib/usrp/n230/n230_eeprom_manager.cpp b/host/lib/usrp/n230/n230_eeprom_manager.cpp index d9d02c58c..c21eb9ddb 100644 --- a/host/lib/usrp/n230/n230_eeprom_manager.cpp +++ b/host/lib/usrp/n230/n230_eeprom_manager.cpp @@ -17,7 +17,7 @@  #include "n230_eeprom.h"  #include <uhd/utils/byteswap.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/exception.hpp>  #include <uhd/types/mac_addr.hpp>  #include <boost/format.hpp> diff --git a/host/lib/usrp/n230/n230_frontend_ctrl.cpp b/host/lib/usrp/n230/n230_frontend_ctrl.cpp index 3d81721ec..80f1232b1 100644 --- a/host/lib/usrp/n230/n230_frontend_ctrl.cpp +++ b/host/lib/usrp/n230/n230_frontend_ctrl.cpp @@ -17,7 +17,7 @@  #include "n230_frontend_ctrl.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/exception.hpp>  #include <uhd/types/dict.hpp>  #include <boost/format.hpp> diff --git a/host/lib/usrp/common/fw_comm_protocol.h b/host/lib/usrp/n230/n230_fw_comm_protocol.h index 14adb33a9..b7c85f2ba 100644 --- a/host/lib/usrp/common/fw_comm_protocol.h +++ b/host/lib/usrp/n230/n230_fw_comm_protocol.h @@ -15,8 +15,8 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#ifndef INCLUDED_FW_COMM_PROTOCOL -#define INCLUDED_FW_COMM_PROTOCOL +#ifndef INCLUDED_N230_FW_COMM_PROTOCOL +#define INCLUDED_N230_FW_COMM_PROTOCOL  #include <stdint.h>  #ifndef __cplusplus @@ -99,4 +99,4 @@ bool process_fw_comm_protocol_pkt(  #endif  //ifdef __cplusplus -#endif /* INCLUDED_FW_COMM_PROTOCOL */ +#endif /* INCLUDED_N230_FW_COMM_PROTOCOL */ diff --git a/host/lib/usrp/common/usrp3_fw_ctrl_iface.cpp b/host/lib/usrp/n230/n230_fw_ctrl_iface.cpp index 16ee84140..18c2c4cf8 100644 --- a/host/lib/usrp/common/usrp3_fw_ctrl_iface.cpp +++ b/host/lib/usrp/n230/n230_fw_ctrl_iface.cpp @@ -15,34 +15,33 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include "usrp3_fw_ctrl_iface.hpp" +#include "n230_fw_ctrl_iface.hpp"  #include <uhd/utils/byteswap.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/exception.hpp>  #include <boost/format.hpp>  #include <boost/asio.hpp> //used for htonl and ntohl -#include <boost/foreach.hpp> -#include "fw_comm_protocol.h" +#include "n230_fw_comm_protocol.h" -namespace uhd { namespace usrp { namespace usrp3 { +namespace uhd { namespace usrp { namespace n230 {  //----------------------------------------------------------  // Factory method  //---------------------------------------------------------- -uhd::wb_iface::sptr usrp3_fw_ctrl_iface::make( +uhd::wb_iface::sptr n230_fw_ctrl_iface::make(      uhd::transport::udp_simple::sptr udp_xport,      const uint16_t product_id,      const bool verbose)  { -    return wb_iface::sptr(new usrp3_fw_ctrl_iface(udp_xport, product_id, verbose)); +    return wb_iface::sptr(new n230_fw_ctrl_iface(udp_xport, product_id, verbose));  }  //----------------------------------------------------------  // udp_fw_ctrl_iface  //---------------------------------------------------------- -usrp3_fw_ctrl_iface::usrp3_fw_ctrl_iface( +n230_fw_ctrl_iface::n230_fw_ctrl_iface(      uhd::transport::udp_simple::sptr udp_xport,      const uint16_t product_id,      const bool verbose) : @@ -53,18 +52,18 @@ usrp3_fw_ctrl_iface::usrp3_fw_ctrl_iface(      peek32(0);  } -usrp3_fw_ctrl_iface::~usrp3_fw_ctrl_iface() +n230_fw_ctrl_iface::~n230_fw_ctrl_iface()  {      flush();  } -void usrp3_fw_ctrl_iface::flush() +void n230_fw_ctrl_iface::flush()  {      boost::mutex::scoped_lock lock(_mutex);      _flush();  } -void usrp3_fw_ctrl_iface::poke32(const wb_addr_type addr, const uint32_t data) +void n230_fw_ctrl_iface::poke32(const wb_addr_type addr, const uint32_t data)  {      boost::mutex::scoped_lock lock(_mutex); @@ -75,13 +74,13 @@ void usrp3_fw_ctrl_iface::poke32(const wb_addr_type addr, const uint32_t data)          } catch(const std::exception &ex) {              const std::string error_msg = str(boost::format(                  "udp fw poke32 failure #%u\n%s") % i % ex.what()); -            if (_verbose) UHD_MSG(warning) << error_msg << std::endl; +            if (_verbose) UHD_LOGGER_WARNING("N230") << error_msg ;              if (i == NUM_RETRIES) throw uhd::io_error(error_msg);          }      }  } -uint32_t usrp3_fw_ctrl_iface::peek32(const wb_addr_type addr) +uint32_t n230_fw_ctrl_iface::peek32(const wb_addr_type addr)  {      boost::mutex::scoped_lock lock(_mutex); @@ -91,14 +90,14 @@ uint32_t usrp3_fw_ctrl_iface::peek32(const wb_addr_type addr)          } catch(const std::exception &ex) {              const std::string error_msg = str(boost::format(                  "udp fw peek32 failure #%u\n%s") % i % ex.what()); -            if (_verbose) UHD_MSG(warning) << error_msg << std::endl; +            if (_verbose) UHD_LOGGER_WARNING("N230") << error_msg ;              if (i == NUM_RETRIES) throw uhd::io_error(error_msg);          }      }      return 0;  } -void usrp3_fw_ctrl_iface::_poke32(const wb_addr_type addr, const uint32_t data) +void n230_fw_ctrl_iface::_poke32(const wb_addr_type addr, const uint32_t data)  {      //Load request struct      fw_comm_pkt_t request; @@ -129,7 +128,7 @@ void usrp3_fw_ctrl_iface::_poke32(const wb_addr_type addr, const uint32_t data)      UHD_ASSERT_THROW(reply.data[0] == request.data[0]);  } -uint32_t usrp3_fw_ctrl_iface::_peek32(const wb_addr_type addr) +uint32_t n230_fw_ctrl_iface::_peek32(const wb_addr_type addr)  {      //Load request struct      fw_comm_pkt_t request; @@ -162,7 +161,7 @@ uint32_t usrp3_fw_ctrl_iface::_peek32(const wb_addr_type addr)      return uhd::ntohx<uint32_t>(reply.data[0]);  } -void usrp3_fw_ctrl_iface::_flush(void) +void n230_fw_ctrl_iface::_flush(void)  {      char buff[FW_COMM_PROTOCOL_MTU] = {};      while (_udp_xport->recv(boost::asio::buffer(buff), 0.0)) { @@ -170,7 +169,7 @@ void usrp3_fw_ctrl_iface::_flush(void)      }  } -std::vector<std::string> usrp3_fw_ctrl_iface::discover_devices( +std::vector<std::string> n230_fw_ctrl_iface::discover_devices(      const std::string& addr_hint, const std::string& port,      uint16_t product_id)  { @@ -183,8 +182,8 @@ std::vector<std::string> usrp3_fw_ctrl_iface::discover_devices(      try {          udp_bcast_xport = uhd::transport::udp_simple::make_broadcast(addr_hint, port);      } catch(const std::exception &e) { -        UHD_MSG(error) << boost::format("Cannot open UDP transport on %s for discovery\n%s") -        % addr_hint % e.what() << std::endl; +        UHD_LOGGER_ERROR("N230") << boost::format("Cannot open UDP transport on %s for discovery\n%s") +        % addr_hint % e.what() ;          return addrs;      } @@ -213,7 +212,7 @@ std::vector<std::string> usrp3_fw_ctrl_iface::discover_devices(      return addrs;  } -uint32_t usrp3_fw_ctrl_iface::get_iface_id( +uint32_t n230_fw_ctrl_iface::get_iface_id(      const std::string& addr, const std::string& port,      uint16_t product_id)  { diff --git a/host/lib/usrp/common/usrp3_fw_ctrl_iface.hpp b/host/lib/usrp/n230/n230_fw_ctrl_iface.hpp index 9dc35ef9e..675c843b3 100644 --- a/host/lib/usrp/common/usrp3_fw_ctrl_iface.hpp +++ b/host/lib/usrp/n230/n230_fw_ctrl_iface.hpp @@ -15,24 +15,24 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#ifndef INCLUDED_LIBUHD_USRP_USRP3_UDP_FW_CTRL_IFACE_HPP -#define INCLUDED_LIBUHD_USRP_USRP3_UDP_FW_CTRL_IFACE_HPP +#ifndef INCLUDED_LIBUHD_USRP_N230_UDP_FW_CTRL_IFACE_HPP +#define INCLUDED_LIBUHD_USRP_N230_UDP_FW_CTRL_IFACE_HPP  #include <uhd/types/wb_iface.hpp>  #include <uhd/transport/udp_simple.hpp>  #include <boost/thread/mutex.hpp>  #include <vector> -namespace uhd { namespace usrp { namespace usrp3 { +namespace uhd { namespace usrp { namespace n230 { -class usrp3_fw_ctrl_iface : public uhd::wb_iface +class n230_fw_ctrl_iface : public uhd::wb_iface  {  public: -    usrp3_fw_ctrl_iface( +    n230_fw_ctrl_iface(          uhd::transport::udp_simple::sptr udp_xport,          const uint16_t product_id,          const bool verbose); -    virtual ~usrp3_fw_ctrl_iface(); +    virtual ~n230_fw_ctrl_iface();      // -- uhd::wb_iface --      void poke32(const wb_addr_type addr, const uint32_t data); @@ -69,4 +69,4 @@ private:  }}} //namespace -#endif //INCLUDED_LIBUHD_USRP_USRP3_USRP3_UDP_FW_CTRL_HPP +#endif // INCLUDED_LIBUHD_USRP_N230_UDP_FW_CTRL_IFACE_HPP diff --git a/host/lib/usrp/n230/n230_impl.cpp b/host/lib/usrp/n230/n230_impl.cpp index 015140fcc..63971fb34 100644 --- a/host/lib/usrp/n230/n230_impl.cpp +++ b/host/lib/usrp/n230/n230_impl.cpp @@ -17,7 +17,7 @@  #include "n230_impl.hpp" -#include "usrp3_fw_ctrl_iface.hpp" +#include "n230_fw_ctrl_iface.hpp"  #include "validate_subdev_spec.hpp"  #include <uhd/utils/static.hpp>  #include <uhd/transport/if_addrs.hpp> @@ -25,7 +25,7 @@  #include <uhd/usrp/subdev_spec.hpp>  #include <uhd/utils/byteswap.hpp>  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/types/sensors.hpp>  #include <uhd/types/ranges.hpp>  #include <uhd/types/direction.hpp> @@ -33,7 +33,6 @@  #include <uhd/usrp/dboard_eeprom.hpp>  #include <uhd/usrp/gps_ctrl.hpp>  #include <boost/format.hpp> -#include <boost/foreach.hpp>  #include <boost/lexical_cast.hpp>  #include <boost/bind.hpp>  #include <boost/algorithm/string.hpp> @@ -42,7 +41,6 @@  #include <boost/asio.hpp> //used for htonl and ntohl  #include <boost/make_shared.hpp> -#include "../common/fw_comm_protocol.h"  #include "n230_defaults.h"  #include "n230_fpga_defs.h"  #include "n230_fw_defs.h" @@ -71,7 +69,7 @@ uhd::device_addrs_t n230_impl::n230_find(const uhd::device_addr_t &multi_dev_hin      if (hints.size() > 1){          device_addrs_t found_devices;          std::string error_msg; -        BOOST_FOREACH(const device_addr_t &hint_i, hints){ +        for(const device_addr_t &hint_i:  hints){              device_addrs_t found_devices_i = n230_find(hint_i);              if (found_devices_i.size() != 1) error_msg += str(boost::format(                  "Could not resolve device hint \"%s\" to a single device." @@ -98,7 +96,7 @@ uhd::device_addrs_t n230_impl::n230_find(const uhd::device_addr_t &multi_dev_hin      //if no address was specified, send a broadcast on each interface      if (not hint.has_key("addr")) { -        BOOST_FOREACH(const if_addrs_t &if_addrs, get_if_addrs()) { +        for(const if_addrs_t &if_addrs:  get_if_addrs()) {              //avoid the loopback device              if (if_addrs.inet == asio::ip::address_v4::loopback().to_string()) continue; @@ -116,10 +114,10 @@ uhd::device_addrs_t n230_impl::n230_find(const uhd::device_addr_t &multi_dev_hin      }      std::vector<std::string> discovered_addrs = -        usrp3::usrp3_fw_ctrl_iface::discover_devices( +        n230_fw_ctrl_iface::discover_devices(              hint["addr"], BOOST_STRINGIZE(N230_FW_COMMS_UDP_PORT), N230_FW_PRODUCT_ID); -    BOOST_FOREACH(const std::string& addr, discovered_addrs) +    for(const std::string& addr:  discovered_addrs)      {          device_addr_t new_addr;          new_addr["type"] = "n230"; @@ -136,10 +134,10 @@ uhd::device_addrs_t n230_impl::n230_find(const uhd::device_addr_t &multi_dev_hin          //connected communication can fail. Retry the following call to allow          //the stack to update          size_t first_conn_retries = 10; -        usrp3::usrp3_fw_ctrl_iface::sptr fw_ctrl; +        n230_fw_ctrl_iface::sptr fw_ctrl;          while (first_conn_retries > 0) {              try { -                fw_ctrl = usrp3::usrp3_fw_ctrl_iface::make(ctrl_xport, N230_FW_PRODUCT_ID, false /*verbose*/); +                fw_ctrl = n230_fw_ctrl_iface::make(ctrl_xport, N230_FW_PRODUCT_ID, false /*verbose*/);                  break;              } catch (uhd::io_error& ex) {                  boost::this_thread::sleep(boost::posix_time::milliseconds(500)); @@ -192,7 +190,7 @@ device::sptr n230_impl::n230_make(const device_addr_t &device_addr)   **********************************************************************/  n230_impl::n230_impl(const uhd::device_addr_t& dev_addr)  { -    UHD_MSG(status) << "N230 initialization sequence..." << std::endl; +    UHD_LOGGER_INFO("N230") << "N230 initialization sequence...";      _dev_args.parse(dev_addr);      _tree = uhd::property_tree::make(); @@ -210,9 +208,9 @@ n230_impl::n230_impl(const uhd::device_addr_t& dev_addr)      const mboard_eeprom_t& mb_eeprom = _eeprom_mgr->get_mb_eeprom();      bool recover_mb_eeprom = dev_addr.has_key("recover_mb_eeprom");      if (recover_mb_eeprom) { -        UHD_MSG(warning) << "UHD is operating in EEPROM Recovery Mode which disables hardware version " +        UHD_LOGGER_WARNING("N230") << "UHD is operating in EEPROM Recovery Mode which disables hardware version "                              "checks.\nOperating in this mode may cause hardware damage and unstable " -                            "radio performance!"<< std::endl; +                            "radio performance!";      }      uint16_t hw_rev = boost::lexical_cast<uint16_t>(mb_eeprom["revision"]);      uint16_t hw_rev_compat = boost::lexical_cast<uint16_t>(mb_eeprom["revision_compat"]); @@ -234,11 +232,11 @@ n230_impl::n230_impl(const uhd::device_addr_t& dev_addr)      //Debug loopback mode      switch(_dev_args.get_loopback_mode()) {      case n230_device_args_t::LOOPBACK_RADIO: -        UHD_MSG(status) << "DEBUG: Running in TX->RX Radio loopback mode.\n"; +        UHD_LOGGER_INFO("N230") << "DEBUG: Running in TX->RX Radio loopback mode.";          _resource_mgr->get_frontend_ctrl().set_self_test_mode(LOOPBACK_RADIO);          break;      case n230_device_args_t::LOOPBACK_CODEC: -        UHD_MSG(status) << "DEBUG: Running in TX->RX CODEC loopback mode.\n"; +        UHD_LOGGER_INFO("N230") << "DEBUG: Running in TX->RX CODEC loopback mode.";          _resource_mgr->get_frontend_ctrl().set_self_test_mode(LOOPBACK_CODEC);          break;      default: @@ -397,11 +395,11 @@ void n230_impl::_initialize_property_tree(const fs_path& mb_path)      // Initialize subdev specs      //------------------------------------------------------------------      subdev_spec_t rx_spec, tx_spec; -    BOOST_FOREACH(const std::string &fe, _tree->list(mb_path / "dboards" / "A" / "rx_frontends")) +    for(const std::string &fe:  _tree->list(mb_path / "dboards" / "A" / "rx_frontends"))      {          rx_spec.push_back(subdev_spec_pair_t("A", fe));      } -    BOOST_FOREACH(const std::string &fe, _tree->list(mb_path / "dboards" / "A" / "tx_frontends")) +    for(const std::string &fe:  _tree->list(mb_path / "dboards" / "A" / "tx_frontends"))      {          tx_spec.push_back(subdev_spec_pair_t("A", fe));      } @@ -437,7 +435,7 @@ void n230_impl::_initialize_property_tree(const fs_path& mb_path)      //------------------------------------------------------------------      if (_resource_mgr->is_gpsdo_present()) {          uhd::gps_ctrl::sptr gps_ctrl = _resource_mgr->get_gps_ctrl(); -        BOOST_FOREACH(const std::string &name, gps_ctrl->get_sensors()) +        for(const std::string &name:  gps_ctrl->get_sensors())          {              _tree->create<sensor_value_t>(mb_path / "sensors" / name)                  .set_publisher(boost::bind(&gps_ctrl::get_sensor, gps_ctrl, name)); @@ -499,7 +497,7 @@ void n230_impl::_initialize_radio_properties(const fs_path& mb_path, size_t inst      //RF Frontend Interfacing      static const std::vector<direction_t> data_directions = boost::assign::list_of(RX_DIRECTION)(TX_DIRECTION); -    BOOST_FOREACH(direction_t direction, data_directions) { +    for(direction_t direction:  data_directions) {          const std::string dir_str = (direction == RX_DIRECTION) ? "rx" : "tx";          const std::string key = boost::to_upper_copy(dir_str) + str(boost::format("%u") % (instance + 1));          const fs_path rf_fe_path = mb_path / "dboards" / "A" / (dir_str + "_frontends") / ((instance==0)?"A":"B"); diff --git a/host/lib/usrp/n230/n230_resource_manager.cpp b/host/lib/usrp/n230/n230_resource_manager.cpp index b96de542a..61a80ae43 100644 --- a/host/lib/usrp/n230/n230_resource_manager.cpp +++ b/host/lib/usrp/n230/n230_resource_manager.cpp @@ -17,11 +17,11 @@  #include "n230_resource_manager.hpp" -#include "usrp3_fw_ctrl_iface.hpp" +#include "n230_fw_ctrl_iface.hpp"  #include <uhd/transport/if_addrs.hpp>  #include <uhd/transport/udp_zero_copy.hpp>  #include <uhd/utils/byteswap.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/platform.hpp>  #include <uhd/utils/paths.hpp>  #include <boost/format.hpp> @@ -58,7 +58,7 @@ public:          }      }      clocking_mode_t get_clocking_mode() { -        return AD9361_XTAL_N_CLK_PATH; +        return clocking_mode_t::AD9361_XTAL_N_CLK_PATH;      }      digital_interface_mode_t get_digital_interface_mode() {          return AD9361_DDR_FDD_LVDS; @@ -80,18 +80,18 @@ n230_resource_manager::n230_resource_manager(      _safe_mode(safe_mode),      _last_host_enpoint(0)  { -    if (_safe_mode) UHD_MSG(warning) << "Initializing device in safe mode\n"; -    UHD_MSG(status) << "Setup basic communication...\n"; +    if (_safe_mode) UHD_LOGGER_WARNING("N230") << "Initializing device in safe mode\n"; +    UHD_LOGGER_INFO("N230") << "Setup basic communication...";      //Discover ethernet interfaces      bool dual_eth_expected = (ip_addrs.size() > 1); -    BOOST_FOREACH(const std::string& addr, ip_addrs) { +    for(const std::string& addr:  ip_addrs) {          n230_eth_conn_t conn_iface;          conn_iface.ip_addr = addr;          uint32_t iface_id = 0xFFFFFFFF;          try { -            iface_id = usrp3::usrp3_fw_ctrl_iface::get_iface_id( +            iface_id = n230::n230_fw_ctrl_iface::get_iface_id(                  conn_iface.ip_addr, BOOST_STRINGIZE(N230_FW_COMMS_UDP_PORT), N230_FW_PRODUCT_ID);          } catch (uhd::io_error&) {              throw uhd::io_error(str(boost::format( @@ -118,7 +118,7 @@ n230_resource_manager::n230_resource_manager(      }      //Create firmware communication interface -    _fw_ctrl = usrp3::usrp3_fw_ctrl_iface::make( +    _fw_ctrl = n230::n230_fw_ctrl_iface::make(          transport::udp_simple::make_connected(              _get_conn(PRI_ETH).ip_addr, BOOST_STRINGIZE(N230_FW_COMMS_UDP_PORT)), N230_FW_PRODUCT_ID);      if (_fw_ctrl.get() == NULL) { @@ -145,7 +145,7 @@ n230_resource_manager::n230_resource_manager(      }      _check_fpga_compat(); -    UHD_MSG(status) << boost::format("Version signatures... Firmware:%s FPGA:%s...\n") +    UHD_LOGGER_INFO("N230") << boost::format("Version signatures... Firmware:%s FPGA:%s...")          % _fw_version.get_hash_str() % _fpga_version.get_hash_str();      _core_radio_ctrl_reg.initialize(*_core_ctrl, true /*flush*/); @@ -160,7 +160,7 @@ n230_resource_manager::n230_resource_manager(      }      //Create AD9361 interface -    UHD_MSG(status) << "Initializing CODEC...\n"; +    UHD_LOGGER_INFO("N230") << "Initializing CODEC...";      _codec_ctrl = ad9361_ctrl::make_spi(          boost::make_shared<n230_ad9361_client_t>(), _core_spi_ctrl, fpga::AD9361_SPI_SLAVE_NUM);      if (_codec_ctrl.get() == NULL) { @@ -210,7 +210,7 @@ n230_resource_manager::n230_resource_manager(      //Create GPSDO interface      if (_core_status_reg.read(fpga::core_status_reg_t::GPSDO_STATUS) != fpga::GPSDO_ST_ABSENT) { -        UHD_MSG(status) << "Detecting GPSDO.... " << std::flush; +        UHD_LOGGER_INFO("N230") << "Detecting GPSDO.... ";          try {              const sid_t gps_uart_sid = _generate_sid(GPS_UART, _get_conn(PRI_ETH).type);              transport::zero_copy_if::sptr gps_uart_xport = @@ -221,7 +221,7 @@ n230_resource_manager::n230_resource_manager(              boost::this_thread::sleep(boost::posix_time::seconds(1)); //allow for a little propagation              _gps_ctrl = gps_ctrl::make(_gps_uart);          } catch(std::exception &e) { -            UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl; +            UHD_LOGGER_ERROR("N230") << "An error occurred making GPSDO control: " << e.what() ;          }          if (not is_gpsdo_present()) {              _core_ctrl->poke32(fpga::sr_addr(fpga::SR_CORE_GPSDO_ST), fpga::GPSDO_ST_ABSENT); @@ -276,7 +276,7 @@ transport::zero_copy_if::sptr n230_resource_manager::create_transport(      return xport;  } -bool n230_resource_manager::is_device_claimed(uhd::usrp::usrp3::usrp3_fw_ctrl_iface::sptr fw_ctrl) +bool n230_resource_manager::is_device_claimed(n230_fw_ctrl_iface::sptr fw_ctrl)  {      boost::mutex::scoped_lock(_claimer_mutex); @@ -488,7 +488,7 @@ bool n230_resource_manager::_radio_data_loopback_self_test(wb_iface::sptr iface)          const uint32_t rb_rx = uint32_t(rb_word64 & 0xffffffff);          test_fail = word32 != rb_tx or word32 != rb_rx;          if (test_fail){ -            UHD_MSG(fastpath) << boost::format("mismatch (exp:%x, got:%x and %x)... ") % word32 % rb_tx % rb_rx; +            UHD_LOG_ERROR("N230", str(boost::format("mismatch (exp:%x, got:%x and %x)... ") % word32 % rb_tx % rb_rx));              break; //exit loop on any failure          }      } diff --git a/host/lib/usrp/n230/n230_resource_manager.hpp b/host/lib/usrp/n230/n230_resource_manager.hpp index 180f4f437..6da3b9035 100644 --- a/host/lib/usrp/n230/n230_resource_manager.hpp +++ b/host/lib/usrp/n230/n230_resource_manager.hpp @@ -37,7 +37,7 @@  #include <uhd/transport/bounded_buffer.hpp>  #include <uhd/usrp/gps_ctrl.hpp> -#include "usrp3_fw_ctrl_iface.hpp" +#include "n230_fw_ctrl_iface.hpp"  #include "n230_clk_pps_ctrl.hpp"  #include "n230_cores.hpp"  #include "n230_fpga_defs.h" @@ -98,7 +98,7 @@ public:     //Methods      n230_resource_manager(const std::vector<std::string> ip_addrs, const bool safe_mode);      virtual ~n230_resource_manager(); -    static bool is_device_claimed(uhd::usrp::usrp3::usrp3_fw_ctrl_iface::sptr fw_ctrl); +    static bool is_device_claimed(n230_fw_ctrl_iface::sptr fw_ctrl);      inline bool is_device_claimed() {          if (_fw_ctrl.get()) { @@ -276,12 +276,12 @@ private:      ver_info_t                      _fpga_version;      //Firmware register interface -    uhd::usrp::usrp3::usrp3_fw_ctrl_iface::sptr   _fw_ctrl; +    n230_fw_ctrl_iface::sptr        _fw_ctrl;      uhd::task::sptr                 _claimer_task;      static boost::mutex             _claimer_mutex;  //All claims and checks in this process are serialized      //Transport -    uint8_t                  _last_host_enpoint; +    uint8_t                         _last_host_enpoint;      //Radio settings interface      radio_ctrl_core_3000::sptr      _core_ctrl; diff --git a/host/lib/usrp/n230/n230_stream_manager.cpp b/host/lib/usrp/n230/n230_stream_manager.cpp index 0528212d0..95da2752e 100644 --- a/host/lib/usrp/n230/n230_stream_manager.cpp +++ b/host/lib/usrp/n230/n230_stream_manager.cpp @@ -24,7 +24,6 @@  #include <boost/bind.hpp>  #include <uhd/utils/tasks.hpp>  #include <uhd/utils/log.hpp> -#include <boost/foreach.hpp>  #include <boost/make_shared.hpp>  static const double N230_RX_SW_BUFF_FULL_FACTOR   = 0.90;     //Buffer should ideally be 90% full. @@ -478,7 +477,7 @@ void n230_stream_manager::_handle_tx_async_msgs(          _cvita_hdr_unpack(packet_buff, if_packet_info);          endian_conv = uhd::ntohx;      } catch(const std::exception &ex) { -        UHD_MSG(error) << "Error parsing async message packet: " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("N230") << "Error parsing async message packet: " << ex.what() ;          return;      } diff --git a/host/lib/usrp/n230/n230_uart.cpp b/host/lib/usrp/n230/n230_uart.cpp index 7291a7276..7330dff4a 100644 --- a/host/lib/usrp/n230/n230_uart.cpp +++ b/host/lib/usrp/n230/n230_uart.cpp @@ -20,7 +20,7 @@  #include <uhd/transport/bounded_buffer.hpp>  #include <uhd/transport/vrt_if_packet.hpp>  #include <uhd/utils/byteswap.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/types/time_spec.hpp>  #include <uhd/exception.hpp> diff --git a/host/lib/usrp/subdev_spec.cpp b/host/lib/usrp/subdev_spec.cpp index 6912afec8..b7eb64f87 100644 --- a/host/lib/usrp/subdev_spec.cpp +++ b/host/lib/usrp/subdev_spec.cpp @@ -20,7 +20,6 @@  #include <boost/algorithm/string.hpp> //for split  #include <boost/tokenizer.hpp>  #include <boost/format.hpp> -#include <boost/foreach.hpp>  #include <sstream>  #include <vector> @@ -44,8 +43,16 @@ bool usrp::operator==(const subdev_spec_pair_t &lhs, const subdev_spec_pair_t &r      return (lhs.db_name == rhs.db_name) and (lhs.sd_name == rhs.sd_name);  } +bool subdev_spec_pair_t::operator==(const subdev_spec_pair_t &other){ +    return (other.db_name == db_name) and (other.sd_name == sd_name); +} + +bool subdev_spec_pair_t::operator!=(const subdev_spec_pair_t &other){ +    return (other.db_name != db_name) or (other.sd_name != sd_name); +} +  subdev_spec_t::subdev_spec_t(const std::string &markup){ -    BOOST_FOREACH(const std::string &pair, pair_tokenizer(markup)){ +    for(const std::string &pair:  pair_tokenizer(markup)){          if (pair.empty()) continue;          std::vector<std::string> db_sd; boost::split(db_sd, pair, boost::is_any_of(":"));          switch(db_sd.size()){ @@ -62,7 +69,7 @@ std::string subdev_spec_t::to_pp_string(void) const{      std::stringstream ss;      size_t count = 0;      ss << "Subdevice Specification:" << std::endl; -    BOOST_FOREACH(const subdev_spec_pair_t &pair, *this){ +    for(const subdev_spec_pair_t &pair:  *this){          ss << boost::format(              "    Channel %d: Daughterboard %s, Subdevice %s"          ) % (count++) % pair.db_name % pair.sd_name << std::endl; @@ -73,7 +80,7 @@ std::string subdev_spec_t::to_pp_string(void) const{  std::string subdev_spec_t::to_string(void) const{      std::string markup;      size_t count = 0; -    BOOST_FOREACH(const subdev_spec_pair_t &pair, *this){ +    for(const subdev_spec_pair_t &pair:  *this){          markup += ((count++)? " " : "") + pair.db_name + ":" + pair.sd_name;      }      return markup; diff --git a/host/lib/usrp/usrp1/codec_ctrl.cpp b/host/lib/usrp/usrp1/codec_ctrl.cpp index 4c811d5e2..bb81ec3e7 100644 --- a/host/lib/usrp/usrp1/codec_ctrl.cpp +++ b/host/lib/usrp/usrp1/codec_ctrl.cpp @@ -277,9 +277,9 @@ void usrp1_codec_ctrl_impl::send_reg(uint8_t addr)  {      uint32_t reg = _ad9862_regs.get_write_reg(addr); -    UHD_LOGV(often) +    UHD_LOGGER_TRACE("USRP1")          << "codec control write reg: 0x" -        << std::setw(8) << std::hex << reg << std::endl +        << std::setw(8) << std::hex << reg       ;      _iface->write_spi(_spi_slave,                           spi_config_t::EDGE_RISE, reg, 16); @@ -289,17 +289,17 @@ void usrp1_codec_ctrl_impl::recv_reg(uint8_t addr)  {      uint32_t reg = _ad9862_regs.get_read_reg(addr); -    UHD_LOGV(often) +    UHD_LOGGER_TRACE("USRP1")          << "codec control read reg: 0x" -        << std::setw(8) << std::hex << reg << std::endl +        << std::setw(8) << std::hex << reg       ;      uint32_t ret = _iface->read_spi(_spi_slave,                                          spi_config_t::EDGE_RISE, reg, 16); -    UHD_LOGV(often) +    UHD_LOGGER_TRACE("USRP1")          << "codec control read ret: 0x" -        << std::setw(8) << std::hex << ret << std::endl +        << std::setw(8) << std::hex << ret       ;      _ad9862_regs.set_reg(addr, uint16_t(ret)); @@ -389,13 +389,13 @@ void usrp1_codec_ctrl_impl::set_duc_freq(double freq, double rate)      double coarse_freq = coarse_tune(codec_rate, freq);      double fine_freq = fine_tune(codec_rate / 4, freq - coarse_freq); -    UHD_LOG -        << "ad9862 tuning result:" << std::endl -        << "   requested:   " << freq << std::endl -        << "   actual:      " << coarse_freq + fine_freq << std::endl -        << "   coarse freq: " << coarse_freq << std::endl -        << "   fine freq:   " << fine_freq << std::endl -        << "   codec rate:  " << codec_rate << std::endl +    UHD_LOGGER_DEBUG("USRP1") +        << "ad9862 tuning result:"  +        << "   requested:   " << freq  +        << "   actual:      " << coarse_freq + fine_freq  +        << "   coarse freq: " << coarse_freq  +        << "   fine freq:   " << fine_freq  +        << "   codec rate:  " << codec_rate       ;      this->send_reg(20); diff --git a/host/lib/usrp/usrp1/io_impl.cpp b/host/lib/usrp/usrp1/io_impl.cpp index 920023dad..7ed1d8671 100644 --- a/host/lib/usrp/usrp1/io_impl.cpp +++ b/host/lib/usrp/usrp1/io_impl.cpp @@ -22,7 +22,7 @@  #include "../../transport/super_send_packet_handler.hpp"  #include "usrp1_calc_mux.hpp"  #include "usrp1_impl.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/tasks.hpp>  #include <uhd/utils/safe_call.hpp>  #include <uhd/transport/bounded_buffer.hpp> @@ -305,19 +305,19 @@ void usrp1_impl::vandal_conquest_loop(void){          if (_tx_enabled and underflow){              async_metadata.time_spec = _soft_time_ctrl->get_time();              _soft_time_ctrl->get_async_queue().push_with_pop_on_full(async_metadata); -            UHD_MSG(fastpath) << "U"; +            UHD_LOG_FASTPATH("U")          }          if (_rx_enabled and overflow){              inline_metadata.time_spec = _soft_time_ctrl->get_time();              _soft_time_ctrl->get_inline_queue().push_with_pop_on_full(inline_metadata); -            UHD_MSG(fastpath) << "O"; +            UHD_LOG_FASTPATH("O")          }          boost::this_thread::sleep(boost::posix_time::milliseconds(50));      }}      catch(const boost::thread_interrupted &){} //normal exit condition      catch(const std::exception &e){ -        UHD_MSG(error) << "The vandal caught an unexpected exception " << e.what() << std::endl; +        UHD_LOGGER_ERROR("USRP1") << "The vandal caught an unexpected exception " << e.what() ;      }  } @@ -439,7 +439,7 @@ void usrp1_impl::update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){      //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){ +    for(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(); @@ -459,7 +459,7 @@ void usrp1_impl::update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){      //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){ +    for(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(); @@ -500,11 +500,11 @@ double usrp1_impl::update_rx_samp_rate(size_t dspno, const double samp_rate){      const size_t div = this->has_rx_halfband()? 2 : 1;      const size_t rate = boost::math::iround(_master_clock_rate/this->get_rx_dsp_host_rates().clip(samp_rate, true)); -    if (rate < 8 and this->has_rx_halfband()) UHD_MSG(warning) << +    if (rate < 8 and this->has_rx_halfband()) UHD_LOGGER_WARNING("USRP1") <<          "USRP1 cannot achieve decimations below 8 when the half-band filter is present.\n"          "The usrp1_fpga_4rx.rbf file is a special FPGA image without RX half-band filters.\n"          "To load this image, set the device address key/value pair: fpga=usrp1_fpga_4rx.rbf\n" -    << std::endl; +    ;      if (dspno == 0){ //only care if dsp0 is set since its homogeneous          bool s = this->disable_rx(); @@ -548,10 +548,10 @@ double usrp1_impl::update_tx_samp_rate(size_t dspno, const double samp_rate){  void usrp1_impl::update_rates(void){      const fs_path mb_path = "/mboards/0";      this->update_tick_rate(_master_clock_rate); -    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){ +    for(const std::string &name:  _tree->list(mb_path / "rx_dsps")){          _tree->access<double>(mb_path / "rx_dsps" / name / "rate" / "value").update();      } -    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +    for(const std::string &name:  _tree->list(mb_path / "tx_dsps")){          _tree->access<double>(mb_path / "tx_dsps" / name / "rate" / "value").update();      }  } diff --git a/host/lib/usrp/usrp1/usrp1_calc_mux.hpp b/host/lib/usrp/usrp1/usrp1_calc_mux.hpp index 3577a8042..293d9c37c 100644 --- a/host/lib/usrp/usrp1/usrp1_calc_mux.hpp +++ b/host/lib/usrp/usrp1/usrp1_calc_mux.hpp @@ -71,7 +71,7 @@ static uint32_t calc_rx_mux(const std::vector<mapping_pair_t> &mapping){      //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)){ +    for(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++; @@ -83,7 +83,7 @@ static uint32_t calc_rx_mux(const std::vector<mapping_pair_t> &mapping){      //    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( +    if (num_quads != 0 and num_reals != 0) UHD_LOGGER_WARNING("USRP1") << 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"      ); @@ -132,7 +132,7 @@ static uint32_t calc_tx_mux(const std::vector<mapping_pair_t> &mapping){      //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){ +    for(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 diff --git a/host/lib/usrp/usrp1/usrp1_iface.cpp b/host/lib/usrp/usrp1/usrp1_iface.cpp index b65f8fa2f..9390714ae 100644 --- a/host/lib/usrp/usrp1/usrp1_iface.cpp +++ b/host/lib/usrp/usrp1/usrp1_iface.cpp @@ -49,10 +49,10 @@ public:      {          uint32_t swapped = uhd::htonx(value); -        UHD_LOGV(always) +        UHD_LOGGER_TRACE("USRP1")              << "poke32("              << std::dec << std::setw(2) << addr << ", 0x" -            << std::hex << std::setw(8) << value << ")" << std::endl +            << std::hex << std::setw(8) << value << ")"          ;          uint8_t w_index_h = SPI_ENABLE_FPGA & 0xff; @@ -70,9 +70,9 @@ public:      uint32_t peek32(const uint32_t addr)      { -        UHD_LOGV(always) +        UHD_LOGGER_TRACE("USRP1")              << "peek32(" -            << std::dec << std::setw(2) << addr << ")" << std::endl +            << std::dec << std::setw(2) << addr << ")"          ;          uint32_t value_out; @@ -129,12 +129,12 @@ public:                                   size_t num_bits,                                   bool readback)      { -        UHD_LOGV(always) -            << "transact_spi: " << std::endl -            << "  slave: " << which_slave << std::endl -            << "  bits: " << bits << std::endl -            << "  num_bits: " << num_bits << std::endl -            << "  readback: " << readback << std::endl +        UHD_LOGGER_TRACE("USRP1") +            << "transact_spi: " +            << "  slave: " << which_slave +            << "  bits: " << bits +            << "  num_bits: " << num_bits +            << "  readback: " << readback          ;          UHD_ASSERT_THROW((num_bits <= 32) && !(num_bits % 8));          size_t num_bytes = num_bits / 8; diff --git a/host/lib/usrp/usrp1/usrp1_impl.cpp b/host/lib/usrp/usrp1/usrp1_impl.cpp index 09352c5e0..7c479a447 100644 --- a/host/lib/usrp/usrp1/usrp1_impl.cpp +++ b/host/lib/usrp/usrp1/usrp1_impl.cpp @@ -19,7 +19,7 @@  #include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp>  #include <uhd/transport/usb_control.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/cast.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/static.hpp> @@ -76,16 +76,16 @@ static device_addrs_t usrp1_find(const device_addr_t &hint)      //find the usrps and load firmware      size_t found = 0; -    BOOST_FOREACH(usb_device_handle::sptr handle, usb_device_handle::get_device_list(vid, pid)) { +    for(usb_device_handle::sptr handle: usb_device_handle::get_device_list(vid,  pid)) {          //extract the firmware path for the USRP1          std::string usrp1_fw_image;          try{              usrp1_fw_image = find_image_path(hint.get("fw", "usrp1_fw.ihx"));          }          catch(...){ -            UHD_MSG(warning) << boost::format("Could not locate USRP1 firmware. %s") % print_utility_error("uhd_images_downloader.py"); +            UHD_LOGGER_WARNING("USRP1") << boost::format("Could not locate USRP1 firmware. %s") % print_utility_error("uhd_images_downloader.py");          } -        UHD_LOG << "USRP1 firmware image: " << usrp1_fw_image << std::endl; +        UHD_LOGGER_DEBUG("USRP1") << "USRP1 firmware image: " << usrp1_fw_image ;          usb_control::sptr control;          try{control = usb_control::make(handle, 0);} @@ -104,7 +104,7 @@ static device_addrs_t usrp1_find(const device_addr_t &hint)      //search for the device until found or timeout      while (boost::get_system_time() < timeout_time and usrp1_addrs.empty() and found != 0)      { -        BOOST_FOREACH(usb_device_handle::sptr handle, usb_device_handle::get_device_list(vid, pid)) +      for(usb_device_handle::sptr handle: usb_device_handle::get_device_list(vid,  pid))          {              usb_control::sptr control;              try{control = usb_control::make(handle, 0);} @@ -144,14 +144,14 @@ UHD_STATIC_BLOCK(register_usrp1_device){   * Structors   **********************************************************************/  usrp1_impl::usrp1_impl(const device_addr_t &device_addr){ -    UHD_MSG(status) << "Opening a USRP1 device..." << std::endl; +    UHD_LOGGER_INFO("USRP1") << "Opening a USRP1 device...";      _type = device::USRP;      //extract the FPGA path for the USRP1      std::string usrp1_fpga_image = find_image_path(          device_addr.get("fpga", "usrp1_fpga.rbf")      ); -    UHD_LOG << "USRP1 FPGA image: " << usrp1_fpga_image << std::endl; +    UHD_LOGGER_DEBUG("USRP1") << "USRP1 FPGA image: " << usrp1_fpga_image ;      //try to match the given device address with something on the USB bus      std::vector<usb_device_handle::sptr> device_list = @@ -159,7 +159,7 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){      //locate the matching handle in the device list      usb_device_handle::sptr handle; -    BOOST_FOREACH(usb_device_handle::sptr dev_handle, device_list) { +    for(usb_device_handle::sptr dev_handle:  device_list) {          if (dev_handle->get_serial() == device_addr["serial"]){              handle = dev_handle;              break; @@ -190,12 +190,12 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){      _iface->poke32(FR_MODE, 0x00000000);      _iface->poke32(FR_DEBUG_EN, 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 +    UHD_LOGGER_DEBUG("USRP1") +        << "USRP1 Capabilities"  +        << "    number of duc's: " << get_num_ddcs()  +        << "    number of ddc's: " << get_num_ducs()  +        << "    rx halfband:     " << has_rx_halfband()  +        << "    tx halfband:     " << has_tx_halfband()       ;      //////////////////////////////////////////////////////////////////// @@ -232,7 +232,7 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){              _master_clock_rate = boost::lexical_cast<double>(device_addr["mcr"]);          }          catch(const std::exception &e){ -            UHD_MSG(error) << "Error parsing FPGA clock rate from device address: " << e.what() << std::endl; +            UHD_LOGGER_ERROR("USRP1") << "Error parsing FPGA clock rate from device address: " << e.what() ;          }      }      else if (not mb_eeprom["mcr"].empty()){ @@ -240,10 +240,10 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){              _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_LOGGER_ERROR("USRP1") << "Error parsing FPGA clock rate from EEPROM: " << e.what() ;          }      } -    UHD_MSG(status) << boost::format("Using FPGA clock rate of %fMHz...") % (_master_clock_rate/1e6) << std::endl; +    UHD_LOGGER_INFO("USRP1") << boost::format("Using FPGA clock rate of %fMHz...") % (_master_clock_rate/1e6) ;      _tree->create<double>(mb_path / "tick_rate")          .add_coerced_subscriber(boost::bind(&usrp1_impl::update_tick_rate, this, _1))          .set(_master_clock_rate); @@ -251,7 +251,7 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){      ////////////////////////////////////////////////////////////////////      // create codec control objects      //////////////////////////////////////////////////////////////////// -    BOOST_FOREACH(const std::string &db, _dbc.keys()){ +    for(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 fs_path rx_codec_path = mb_path / "rx_codecs" / db;          const fs_path tx_codec_path = mb_path / "tx_codecs" / db; @@ -284,7 +284,7 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){          .set(subdev_spec_t())          .add_coerced_subscriber(boost::bind(&usrp1_impl::update_tx_subdev_spec, this, _1)); -    BOOST_FOREACH(const std::string &db, _dbc.keys()){ +    for(const std::string &db:  _dbc.keys()){          const fs_path rx_fe_path = mb_path / "rx_frontends" / db;          _tree->create<std::complex<double> >(rx_fe_path / "dc_offset" / "value")              .set_coercer(boost::bind(&usrp1_impl::set_rx_dc_offset, this, db, _1)) @@ -349,7 +349,7 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){      ////////////////////////////////////////////////////////////////////      // create dboard control objects      //////////////////////////////////////////////////////////////////// -    BOOST_FOREACH(const std::string &db, _dbc.keys()){ +    for(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; @@ -400,7 +400,7 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){      this->update_rates();      //reset cordic rates and their properties to zero -    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){ +    for(const std::string &name:  _tree->list(mb_path / "rx_dsps")){          _tree->access<double>(mb_path / "rx_dsps" / name / "freq" / "value").set(0.0);      } diff --git a/host/lib/usrp/usrp1/usrp1_impl.hpp b/host/lib/usrp/usrp1/usrp1_impl.hpp index 18c5c8bd3..1aa255f8d 100644 --- a/host/lib/usrp/usrp1/usrp1_impl.hpp +++ b/host/lib/usrp/usrp1/usrp1_impl.hpp @@ -31,7 +31,6 @@  #include <uhd/usrp/dboard_eeprom.hpp>  #include <uhd/usrp/dboard_manager.hpp>  #include <uhd/transport/usb_zero_copy.hpp> -#include <boost/foreach.hpp>  #include <boost/weak_ptr.hpp>  #include <complex> @@ -158,7 +157,7 @@ private:      void enable_tx(bool enb){          _tx_enabled = enb;          _fx2_ctrl->usrp_tx_enable(enb); -        BOOST_FOREACH(const std::string &key, _dbc.keys()) +        for(const std::string &key:  _dbc.keys())          {              _dbc[key].codec->enable_tx_digital(enb);          } diff --git a/host/lib/usrp/usrp2/codec_ctrl.cpp b/host/lib/usrp/usrp2/codec_ctrl.cpp index a0e456708..ec8bcf919 100644 --- a/host/lib/usrp/usrp2/codec_ctrl.cpp +++ b/host/lib/usrp/usrp2/codec_ctrl.cpp @@ -23,7 +23,6 @@  #include <uhd/utils/safe_call.hpp>  #include <uhd/exception.hpp>  #include <stdint.h> -#include <boost/foreach.hpp>  using namespace uhd; @@ -198,7 +197,7 @@ private:      void send_ad9777_reg(uint8_t addr){          uint16_t reg = _ad9777_regs.get_write_reg(addr); -        UHD_LOGV(always) << "send_ad9777_reg: " << std::hex << reg << std::endl; +        UHD_LOGGER_TRACE("USRP2") << "send_ad9777_reg: " << std::hex << reg;          _spiface->write_spi(              SPI_SS_AD9777, spi_config_t::EDGE_RISE,              reg, 16 diff --git a/host/lib/usrp/usrp2/dboard_iface.cpp b/host/lib/usrp/usrp2/dboard_iface.cpp index 1dafe5721..49ad38eaf 100644 --- a/host/lib/usrp/usrp2/dboard_iface.cpp +++ b/host/lib/usrp/usrp2/dboard_iface.cpp @@ -134,7 +134,7 @@ usrp2_dboard_iface::usrp2_dboard_iface(      //reset the aux dacs      _dac_regs[UNIT_RX] = ad5623_regs_t();      _dac_regs[UNIT_TX] = ad5623_regs_t(); -    BOOST_FOREACH(unit_t unit, _dac_regs.keys()){ +    for(unit_t unit:  _dac_regs.keys()){          _dac_regs[unit].data = 1;          _dac_regs[unit].addr = ad5623_regs_t::ADDR_ALL;          _dac_regs[unit].cmd  = ad5623_regs_t::CMD_RESET; diff --git a/host/lib/usrp/usrp2/io_impl.cpp b/host/lib/usrp/usrp2/io_impl.cpp index 224519944..992d70835 100644 --- a/host/lib/usrp/usrp2/io_impl.cpp +++ b/host/lib/usrp/usrp2/io_impl.cpp @@ -23,7 +23,7 @@  #include "usrp2_regs.hpp"  #include "fw_common.h"  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/utils/tasks.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/byteswap.hpp> @@ -209,7 +209,7 @@ void usrp2_impl::io_impl::recv_pirate_loop(                      fc_mon.update_fc_condition(uhd::ntohx(fc_word32));                      continue;                  } -                //else UHD_MSG(often) << "metadata.event_code " << metadata.event_code << std::endl; +                //else UHD_LOGGER_DEBUG("USRP2") << "metadata.event_code " << metadata.event_code;                  async_msg_fifo.push_with_pop_on_full(metadata);                  standard_async_msg_prints(metadata); @@ -218,7 +218,7 @@ void usrp2_impl::io_impl::recv_pirate_loop(                  //TODO unknown received packet, may want to print error...              }          }catch(const std::exception &e){ -            UHD_MSG(error) << "Error in recv pirate loop: " << e.what() << std::endl; +            UHD_LOGGER_ERROR("USRP2") << "Error in recv pirate loop: " << e.what() ;          }      }  } @@ -231,7 +231,7 @@ void usrp2_impl::io_init(void){      _io_impl = UHD_PIMPL_MAKE(io_impl, ());      //init first so we dont have an access race -    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +    for(const std::string &mb:  _mbc.keys()){          //init the tx xport and flow control monitor          _io_impl->tx_xports.push_back(_mbc[mb].tx_dsp_xport);          _io_impl->fc_mons.push_back(flow_control_monitor::sptr(new flow_control_monitor( @@ -241,14 +241,14 @@ void usrp2_impl::io_init(void){      }      //allocate streamer weak ptrs containers -    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +    for(const std::string &mb:  _mbc.keys()){          _mbc[mb].rx_streamers.resize(_mbc[mb].rx_dsps.size());          _mbc[mb].tx_streamers.resize(1/*known to be 1 dsp*/);      }      //create a new pirate thread for each zc if (yarr!!)      size_t index = 0; -    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +    for(const std::string &mb:  _mbc.keys()){          //spawn a new pirate to plunder the recv booty          _io_impl->pirate_tasks.push_back(task::make(boost::bind(              &usrp2_impl::io_impl::recv_pirate_loop, _io_impl.get(), @@ -261,7 +261,7 @@ void usrp2_impl::update_tick_rate(const double rate){      _io_impl->tick_rate = rate; //shadow for async msg      //update the tick rate on all existing streamers -> thread safe -    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +    for(const std::string &mb:  _mbc.keys()){          for (size_t i = 0; i < _mbc[mb].rx_streamers.size(); i++){              boost::shared_ptr<sph::recv_packet_streamer> my_streamer =                  boost::dynamic_pointer_cast<sph::recv_packet_streamer>(_mbc[mb].rx_streamers[i].lock()); @@ -298,15 +298,15 @@ void usrp2_impl::update_tx_samp_rate(const std::string &mb, const size_t dsp, co  }  void usrp2_impl::update_rates(void){ -    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +    for(const std::string &mb:  _mbc.keys()){          fs_path root = "/mboards/" + mb;          _tree->access<double>(root / "tick_rate").update();          //and now that the tick rate is set, init the host rates to something -        BOOST_FOREACH(const std::string &name, _tree->list(root / "rx_dsps")){ +        for(const std::string &name:  _tree->list(root / "rx_dsps")){              _tree->access<double>(root / "rx_dsps" / name / "rate" / "value").update();          } -        BOOST_FOREACH(const std::string &name, _tree->list(root / "tx_dsps")){ +        for(const std::string &name:  _tree->list(root / "tx_dsps")){              _tree->access<double>(root / "tx_dsps" / name / "rate" / "value").update();          }      } @@ -330,7 +330,7 @@ void usrp2_impl::update_rx_subdev_spec(const std::string &which_mb, const subdev      //compute the new occupancy and resize      _mbc[which_mb].rx_chan_occ = spec.size();      size_t nchan = 0; -    BOOST_FOREACH(const std::string &mb, _mbc.keys()) nchan += _mbc[mb].rx_chan_occ; +    for(const std::string &mb:  _mbc.keys()) nchan += _mbc[mb].rx_chan_occ;  }  void usrp2_impl::update_tx_subdev_spec(const std::string &which_mb, const subdev_spec_t &spec){ @@ -346,7 +346,7 @@ void usrp2_impl::update_tx_subdev_spec(const std::string &which_mb, const subdev      //compute the new occupancy and resize      _mbc[which_mb].tx_chan_occ = spec.size();      size_t nchan = 0; -    BOOST_FOREACH(const std::string &mb, _mbc.keys()) nchan += _mbc[mb].tx_chan_occ; +    for(const std::string &mb:  _mbc.keys()) nchan += _mbc[mb].tx_chan_occ;  }  /*********************************************************************** @@ -375,10 +375,10 @@ void usrp2_impl::program_stream_dest(      //user has provided an alternative address and port for destination      if (args.args.has_key("addr") and args.args.has_key("port")){ -        UHD_MSG(status) << boost::format( -            "Programming streaming destination for custom address.\n" -            "IPv4 Address: %s, UDP Port: %s\n" -        ) % args.args["addr"] % args.args["port"] << std::endl; +        UHD_LOGGER_INFO("USRP2") << boost::format( +            "Programming streaming destination for custom address. " +            "IPv4 Address: %s, UDP Port: %s" +            ) % args.args["addr"] % args.args["port"];          asio::io_service io_service;          asio::ip::udp::resolver resolver(io_service); @@ -388,7 +388,7 @@ void usrp2_impl::program_stream_dest(          stream_ctrl.udp_port = uhd::htonx(uint32_t(endpoint.port()));          for (size_t i = 0; i < 3; i++){ -            UHD_MSG(status) << "ARP attempt " << i << std::endl; +            UHD_LOGGER_INFO("USRP2") << "ARP attempt " << i;              managed_send_buffer::sptr send_buff = xport->get_send_buff();              std::memcpy(send_buff->cast<void *>(), &stream_ctrl, sizeof(stream_ctrl));              send_buff->commit(sizeof(stream_ctrl)); @@ -398,7 +398,7 @@ void usrp2_impl::program_stream_dest(              if (recv_buff and recv_buff->size() >= sizeof(uint32_t)){                  const uint32_t result = uhd::ntohx(recv_buff->cast<const uint32_t *>()[0]);                  if (result == 0){ -                    UHD_MSG(status) << "Success! " << std::endl; +                    UHD_LOGGER_INFO("USRP2") << "Success! ";                      return;                  }              } @@ -454,7 +454,7 @@ rx_streamer::sptr usrp2_impl::get_rx_stream(const uhd::stream_args_t &args_){      for (size_t chan_i = 0; chan_i < args.channels.size(); chan_i++){          const size_t chan = args.channels[chan_i];          size_t num_chan_so_far = 0; -        BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        for(const std::string &mb:  _mbc.keys()){              num_chan_so_far += _mbc[mb].rx_chan_occ;              if (chan < num_chan_so_far){                  const size_t dsp = chan + _mbc[mb].rx_chan_occ - num_chan_so_far; @@ -524,7 +524,7 @@ tx_streamer::sptr usrp2_impl::get_tx_stream(const uhd::stream_args_t &args_){          const size_t chan = args.channels[chan_i];          size_t num_chan_so_far = 0;          size_t abs = 0; -        BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +        for(const std::string &mb:  _mbc.keys()){              num_chan_so_far += _mbc[mb].tx_chan_occ;              if (chan < num_chan_so_far){                  const size_t dsp = chan + _mbc[mb].tx_chan_occ - num_chan_so_far; diff --git a/host/lib/usrp/usrp2/n200_image_loader.cpp b/host/lib/usrp/usrp2/n200_image_loader.cpp index c68484600..01a8faa5e 100644 --- a/host/lib/usrp/usrp2/n200_image_loader.cpp +++ b/host/lib/usrp/usrp2/n200_image_loader.cpp @@ -225,7 +225,7 @@ static uhd::device_addr_t n200_find(const image_loader::image_loader_args_t &ima           * this query. If the user supplied specific arguments that           * led to a USRP2, throw an error.           */ -        BOOST_FOREACH(const uhd::device_addr_t &dev, found){ +        for(const uhd::device_addr_t &dev:  found){              rev_xport = udp_simple::make_connected(                              dev.get("addr"),                              BOOST_STRINGIZE(N200_UDP_FW_UPDATE_PORT) @@ -257,7 +257,7 @@ static uhd::device_addr_t n200_find(const image_loader::image_loader_args_t &ima              std::string err_msg = "Could not resolve given args to a single N-Series device.\n"                                    "Applicable devices:\n"; -            BOOST_FOREACH(const uhd::device_addr_t &dev, n200_found){ +            for(const uhd::device_addr_t &dev:  n200_found){                  err_msg += str(boost::format("* %s (addr=%s)\n")                                 % dev.get("hw_rev")                                 % dev.get("addr")); diff --git a/host/lib/usrp/usrp2/usrp2_fifo_ctrl.cpp b/host/lib/usrp/usrp2/usrp2_fifo_ctrl.cpp index 9cd3afc6c..cdd26bbc4 100644 --- a/host/lib/usrp/usrp2/usrp2_fifo_ctrl.cpp +++ b/host/lib/usrp/usrp2/usrp2_fifo_ctrl.cpp @@ -17,7 +17,7 @@  #include "usrp2_regs.hpp"  #include <uhd/exception.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp>  #include <uhd/transport/vrt_if_packet.hpp>  #include "usrp2_fifo_ctrl.hpp" diff --git a/host/lib/usrp/usrp2/usrp2_iface.cpp b/host/lib/usrp/usrp2/usrp2_iface.cpp index 021f0e3e5..ce547bad0 100644 --- a/host/lib/usrp/usrp2/usrp2_iface.cpp +++ b/host/lib/usrp/usrp2/usrp2_iface.cpp @@ -20,14 +20,13 @@  #include "fw_common.h"  #include "usrp2_iface.hpp"  #include <uhd/exception.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/paths.hpp>  #include <uhd/utils/tasks.hpp>  #include <uhd/utils/paths.hpp>  #include <uhd/utils/safe_call.hpp>  #include <uhd/types/dict.hpp>  #include <boost/thread.hpp> -#include <boost/foreach.hpp>  #include <boost/asio.hpp> //used for htonl and ntohl  #include <boost/assign/list_of.hpp>  #include <boost/format.hpp> @@ -269,10 +268,10 @@ public:                  return ctrl_send_and_recv_internal(out_data, lo, hi, CTRL_RECV_TIMEOUT/CTRL_RECV_RETRIES);              }              catch(const timeout_error &e){ -                UHD_MSG(error) +                UHD_LOGGER_ERROR("USRP2")                      << "Control packet attempt " << i                      << ", sequence number " << _ctrl_seq_num -                    << ":\n" << e.what() << std::endl; +                    << ":\n" << e.what() ;              }          }          throw uhd::runtime_error("link dead: timeout waiting for control packet ACK"); diff --git a/host/lib/usrp/usrp2/usrp2_impl.cpp b/host/lib/usrp/usrp2/usrp2_impl.cpp index ee2434fab..78a9acb72 100644 --- a/host/lib/usrp/usrp2/usrp2_impl.cpp +++ b/host/lib/usrp/usrp2/usrp2_impl.cpp @@ -19,7 +19,7 @@  #include "fw_common.h"  #include "apply_corrections.hpp"  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> +  #include <uhd/exception.hpp>  #include <uhd/transport/if_addrs.hpp>  #include <uhd/transport/udp_zero_copy.hpp> @@ -29,7 +29,6 @@  #include <uhd/utils/byteswap.hpp>  #include <uhd/utils/safe_call.hpp>  #include <boost/format.hpp> -#include <boost/foreach.hpp>  #include <boost/lexical_cast.hpp>  #include <boost/bind.hpp>  #include <boost/assign/list_of.hpp> @@ -54,7 +53,7 @@ device_addrs_t usrp2_find(const device_addr_t &hint_){      if (hints.size() > 1){          device_addrs_t found_devices;          std::string error_msg; -        BOOST_FOREACH(const device_addr_t &hint_i, hints){ +        for(const device_addr_t &hint_i:  hints){              device_addrs_t found_devices_i = usrp2_find(hint_i);              if (found_devices_i.size() != 1) error_msg += str(boost::format(                  "Could not resolve device hint \"%s\" to a single device." @@ -81,7 +80,7 @@ device_addrs_t usrp2_find(const device_addr_t &hint_){      //if no address was specified, send a broadcast on each interface      if (not hint.has_key("addr")){ -        BOOST_FOREACH(const if_addrs_t &if_addrs, get_if_addrs()){ +        for(const if_addrs_t &if_addrs:  get_if_addrs()){              //avoid the loopback device              if (if_addrs.inet == asio::ip::address_v4::loopback().to_string()) continue; @@ -106,7 +105,7 @@ device_addrs_t usrp2_find(const device_addr_t &hint_){          udp_transport = udp_simple::make_broadcast(hint["addr"], BOOST_STRINGIZE(USRP2_UDP_CTRL_PORT));      }      catch(const std::exception &e){ -        UHD_MSG(error) << boost::format("Cannot open UDP transport on %s\n%s") % hint["addr"] % e.what() << std::endl; +        UHD_LOGGER_ERROR("USRP2") << boost::format("Cannot open UDP transport on %s\n%s") % hint["addr"] % e.what() ;          return usrp2_addrs; //dont throw, but return empty address so caller can insert      } @@ -120,11 +119,11 @@ device_addrs_t usrp2_find(const device_addr_t &hint_){      }      catch(const std::exception &ex)      { -        UHD_MSG(error) << "USRP2 Network discovery error " << ex.what() << std::endl; +        UHD_LOGGER_ERROR("USRP2") << "USRP2 Network discovery error " << ex.what() ;      }      catch(...)      { -        UHD_MSG(error) << "USRP2 Network discovery unknown error " << std::endl; +        UHD_LOGGER_ERROR("USRP2") << "USRP2 Network discovery unknown error " ;      }      //loop and recieve until the timeout @@ -284,7 +283,7 @@ static zero_copy_if::sptr make_xport(      //only copy hints that contain the filter word      device_addr_t filtered_hints; -    BOOST_FOREACH(const std::string &key, hints.keys()){ +    for(const std::string &key:  hints.keys()){          if (key.find(filter) == std::string::npos) continue;          filtered_hints[key] = hints[key];      } @@ -319,7 +318,7 @@ static zero_copy_if::sptr make_xport(  usrp2_impl::usrp2_impl(const device_addr_t &_device_addr) :      device_addr(_device_addr)  { -    UHD_MSG(status) << "Opening a USRP2/N-Series device..." << std::endl; +    UHD_LOGGER_INFO("USRP2") << "Opening a USRP2/N-Series device...";      //setup the dsp transport hints (default to a large recv buff)      if (not device_addr.has_key("recv_buff_size")){ @@ -356,8 +355,8 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr) :          device_addr["recv_frame_size"] = boost::lexical_cast<std::string>(mtu.recv_mtu);          device_addr["send_frame_size"] = boost::lexical_cast<std::string>(mtu.send_mtu); -        UHD_MSG(status) << boost::format("Current recv frame size: %d bytes") % mtu.recv_mtu << std::endl; -        UHD_MSG(status) << boost::format("Current send frame size: %d bytes") % mtu.send_mtu << std::endl; +        UHD_LOGGER_INFO("USRP2") << boost::format("Current recv frame size: %d bytes") % mtu.recv_mtu; +        UHD_LOGGER_INFO("USRP2") << boost::format("Current send frame size: %d bytes") % mtu.send_mtu;      }      catch(const uhd::not_implemented_error &){          //just ignore this error, makes older fw work... @@ -412,7 +411,7 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr) :              // handle case where the MB EEPROM is not programmed              if (fpga_major == USRP2_FPGA_COMPAT_NUM or fpga_major == N200_FPGA_COMPAT_NUM)              { -                UHD_MSG(warning)  << "Unable to identify device - assuming USRP2/N-Series device" << std::endl; +                UHD_LOGGER_WARNING("USRP2")  << "Unable to identify device - assuming USRP2/N-Series device" ;                  expected_fpga_compat_num = fpga_major;              }          } @@ -433,19 +432,19 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr) :          ////////////////////////////////////////////////////////////////          // construct transports for RX and TX DSPs          //////////////////////////////////////////////////////////////// -        UHD_LOG << "Making transport for RX DSP0..." << std::endl; +        UHD_LOGGER_TRACE("USRP2") << "Making transport for RX DSP0..." ;          _mbc[mb].rx_dsp_xports.push_back(make_xport(              addr, BOOST_STRINGIZE(USRP2_UDP_RX_DSP0_PORT), device_args_i, "recv"          )); -        UHD_LOG << "Making transport for RX DSP1..." << std::endl; +        UHD_LOGGER_TRACE("USRP2") << "Making transport for RX DSP1..." ;          _mbc[mb].rx_dsp_xports.push_back(make_xport(              addr, BOOST_STRINGIZE(USRP2_UDP_RX_DSP1_PORT), device_args_i, "recv"          )); -        UHD_LOG << "Making transport for TX DSP0..." << std::endl; +        UHD_LOGGER_TRACE("USRP2") << "Making transport for TX DSP0..." ;          _mbc[mb].tx_dsp_xport = make_xport(              addr, BOOST_STRINGIZE(USRP2_UDP_TX_DSP0_PORT), device_args_i, "send"          ); -        UHD_LOG << "Making transport for Control..." << std::endl; +        UHD_LOGGER_TRACE("USRP2") << "Making transport for Control..." ;          _mbc[mb].fifo_ctrl_xport = make_xport(              addr, BOOST_STRINGIZE(USRP2_UDP_FIFO_CRTL_PORT), device_addr_t(), ""          ); @@ -536,18 +535,18 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr) :          //otherwise if not disabled, look for the internal GPSDO          if (_mbc[mb].iface->peekfw(U2_FW_REG_HAS_GPSDO) != dont_look_for_gpsdo)          { -            UHD_MSG(status) << "Detecting internal GPSDO.... " << std::flush; +            UHD_LOGGER_INFO("USRP2") << "Detecting internal GPSDO.... ";              try{                  _mbc[mb].gps = gps_ctrl::make(udp_simple::make_uart(udp_simple::make_connected(                      addr, BOOST_STRINGIZE(USRP2_UDP_UART_GPS_PORT)                  )));              }              catch(std::exception &e){ -                UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl; +                UHD_LOGGER_ERROR("USRP2") << "An error occurred making GPSDO control: " << e.what() ;              }              if (_mbc[mb].gps and _mbc[mb].gps->gps_detected())              { -                BOOST_FOREACH(const std::string &name, _mbc[mb].gps->get_sensors()) +                for(const std::string &name:  _mbc[mb].gps->get_sensors())                  {                      _tree->create<sensor_value_t>(mb_path / "sensors" / name)                          .set_publisher(boost::bind(&gps_ctrl::get_sensor, _mbc[mb].gps, name)); @@ -743,12 +742,12 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr) :          //bind frontend corrections to the dboard freq props          const fs_path db_tx_fe_path = mb_path / "dboards" / "A" / "tx_frontends"; -        BOOST_FOREACH(const std::string &name, _tree->list(db_tx_fe_path)){ +        for(const std::string &name:  _tree->list(db_tx_fe_path)){              _tree->access<double>(db_tx_fe_path / name / "freq" / "value")                  .add_coerced_subscriber(boost::bind(&usrp2_impl::set_tx_fe_corrections, this, mb, _1));          }          const fs_path db_rx_fe_path = mb_path / "dboards" / "A" / "rx_frontends"; -        BOOST_FOREACH(const std::string &name, _tree->list(db_rx_fe_path)){ +        for(const std::string &name:  _tree->list(db_rx_fe_path)){              _tree->access<double>(db_rx_fe_path / name / "freq" / "value")                  .add_coerced_subscriber(boost::bind(&usrp2_impl::set_rx_fe_corrections, this, mb, _1));          } @@ -759,14 +758,14 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr) :      //do some post-init tasks      this->update_rates(); -    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +    for(const std::string &mb:  _mbc.keys()){          fs_path root = "/mboards/" + mb;          //reset cordic rates and their properties to zero -        BOOST_FOREACH(const std::string &name, _tree->list(root / "rx_dsps")){ +        for(const std::string &name:  _tree->list(root / "rx_dsps")){              _tree->access<double>(root / "rx_dsps" / name / "freq" / "value").set(0.0);          } -        BOOST_FOREACH(const std::string &name, _tree->list(root / "tx_dsps")){ +        for(const std::string &name:  _tree->list(root / "tx_dsps")){              _tree->access<double>(root / "tx_dsps" / name / "freq" / "value").set(0.0);          } @@ -778,7 +777,7 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr) :          //GPS installed: use external ref, time, and init time spec          if (_mbc[mb].gps and _mbc[mb].gps->gps_detected()){              _mbc[mb].time64->enable_gpsdo(); -            UHD_MSG(status) << "Setting references to the internal GPSDO" << std::endl; +            UHD_LOGGER_INFO("USRP2") << "Setting references to the internal GPSDO" ;              _tree->access<std::string>(root / "time_source/value").set("gpsdo");              _tree->access<std::string>(root / "clock_source/value").set("gpsdo");          } @@ -787,7 +786,7 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr) :  }  usrp2_impl::~usrp2_impl(void){UHD_SAFE_CALL( -    BOOST_FOREACH(const std::string &mb, _mbc.keys()){ +    for(const std::string &mb:  _mbc.keys()){          _mbc[mb].tx_dsp->set_updates(0, 0);      }  )} diff --git a/host/lib/usrp/usrp_c.cpp b/host/lib/usrp/usrp_c.cpp index e97be2abe..3d50bd8be 100644 --- a/host/lib/usrp/usrp_c.cpp +++ b/host/lib/usrp/usrp_c.cpp @@ -23,7 +23,6 @@  #include <uhd/error.h>  #include <uhd/usrp/usrp.h> -#include <boost/foreach.hpp>  #include <boost/thread/mutex.hpp>  #include <string.h> @@ -259,7 +258,7 @@ uhd_error uhd_usrp_find(          uhd::device_addrs_t devs = uhd::device::find(std::string(args), uhd::device::USRP);          (*strings_out)->string_vector_cpp.clear(); -        BOOST_FOREACH(const uhd::device_addr_t &dev, devs){ +        for(const uhd::device_addr_t &dev:  devs){              (*strings_out)->string_vector_cpp.push_back(dev.to_string());          }      ) diff --git a/host/lib/usrp/x300/x300_adc_ctrl.cpp b/host/lib/usrp/x300/x300_adc_ctrl.cpp index fed2ffaf7..d9d0cb168 100644 --- a/host/lib/usrp/x300/x300_adc_ctrl.cpp +++ b/host/lib/usrp/x300/x300_adc_ctrl.cpp @@ -21,7 +21,6 @@  #include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp>  #include <uhd/exception.hpp> -#include <boost/foreach.hpp>  using namespace uhd; diff --git a/host/lib/usrp/x300/x300_adc_dac_utils.cpp b/host/lib/usrp/x300/x300_adc_dac_utils.cpp index 6fd0ca50b..fda0bb6c9 100644 --- a/host/lib/usrp/x300/x300_adc_dac_utils.cpp +++ b/host/lib/usrp/x300/x300_adc_dac_utils.cpp @@ -147,7 +147,7 @@ void x300_impl::self_test_adcs(mboard_members_t& mb, uint32_t ramp_time_ms) {  void x300_impl::extended_adc_test(mboard_members_t& mb, double duration_s)  {      static const size_t SECS_PER_ITER = 5; -    UHD_MSG(status) << boost::format("Running Extended ADC Self-Test (Duration=%.0fs, %ds/iteration)...\n") +    UHD_LOGGER_INFO("X300") << boost::format("Running Extended ADC Self-Test (Duration=%.0fs, %ds/iteration)...")          % duration_s % SECS_PER_ITER;      size_t num_iters = static_cast<size_t>(ceil(duration_s/SECS_PER_ITER)); @@ -159,18 +159,18 @@ void x300_impl::extended_adc_test(mboard_members_t& mb, double duration_s)          time_strm.imbue(std::locale(std::locale::classic(), facet));          time_strm << boost::posix_time::second_clock::local_time();          //Run self-test -        UHD_MSG(status) << boost::format("-- [%s] Iteration %06d... ") % time_strm.str() % (iter+1); +        UHD_LOGGER_INFO("X300") << boost::format("Running ADC Test Iteration %06d... ") % (iter+1);          try {              self_test_adcs(mb, SECS_PER_ITER*1000); -            UHD_MSG(status) << "passed" << std::endl; +            UHD_LOGGER_INFO("X300") << boost::format("ADC Test Iteration %06d passed") % (iter+1);          } catch(std::exception &e) {              num_failures++; -            UHD_MSG(status) << e.what() << std::endl; +            UHD_LOGGER_ERROR("X300") << e.what();          }      }      if (num_failures == 0) { -        UHD_MSG(status) << "Extended ADC Self-Test PASSED\n"; +        UHD_LOGGER_INFO("X300") << "Extended ADC Self-Test PASSED";      } else {          throw uhd::runtime_error(                  (boost::format("Extended ADC Self-Test FAILED!!! (%d/%d failures)\n") % num_failures % num_iters).str()); @@ -184,7 +184,7 @@ void x300_impl::extended_adc_test(mboard_members_t& mb, double duration_s)  void x300_impl::self_cal_adc_capture_delay(mboard_members_t& mb, const size_t radio_i, bool print_status)  {      radio_perifs_t& perif = mb.radio_perifs[radio_i]; -    if (print_status) UHD_MSG(status) << "Running ADC capture delay self-cal..." << std::flush; +    if (print_status) UHD_LOGGER_INFO("X300") << "Running ADC capture delay self-cal...";      static const uint32_t NUM_DELAY_STEPS = 32;   //The IDELAYE2 element has 32 steps      static const uint32_t NUM_RETRIES     = 2;    //Retry self-cal if it fails in warmup situations @@ -247,7 +247,7 @@ void x300_impl::self_cal_adc_capture_delay(mboard_members_t& mb, const size_t ra                      }                  }              } -            //UHD_MSG(status) << (boost::format("CapTap=%d, Error=%d\n") % dly_tap % err_code); +            //UHD_LOGGER_INFO("X300") << (boost::format("CapTap=%d, Error=%d") % dly_tap % err_code);          }          //Retry the self-cal if it fails @@ -277,13 +277,13 @@ void x300_impl::self_cal_adc_capture_delay(mboard_members_t& mb, const size_t ra      if (print_status) {          double tap_delay = (1.0e12 / mb.clock->get_master_clock_rate()) / (2*32); //in ps -        UHD_MSG(status) << boost::format(" done (Tap=%d, Window=%d, TapDelay=%.3fps, Iter=%d)\n") % ideal_tap % (win_stop-win_start) % tap_delay % iter; +        UHD_LOGGER_INFO("X300") << boost::format(" ADC capture delay self-cal done (Tap=%d, Window=%d, TapDelay=%.3fps, Iter=%d)") % ideal_tap % (win_stop-win_start) % tap_delay % iter;      }  }  double x300_impl::self_cal_adc_xfer_delay(mboard_members_t& mb, bool apply_delay)  { -    UHD_MSG(status) << "Running ADC transfer delay self-cal: " << std::flush; +    UHD_LOGGER_INFO("X300") << "Running ADC transfer delay self-cal: ";      //Effective resolution of the self-cal.      static const size_t NUM_DELAY_STEPS = 100; @@ -293,7 +293,6 @@ double x300_impl::self_cal_adc_xfer_delay(mboard_members_t& mb, bool apply_delay      double delay_range = 2 * master_clk_period;      double delay_incr = delay_range / NUM_DELAY_STEPS; -    UHD_MSG(status) << "Measuring..." << std::flush;      double cached_clk_delay = mb.clock->get_clock_delay(X300_CLOCK_WHICH_ADC0);      double fpga_clk_delay = mb.clock->get_clock_delay(X300_CLOCK_WHICH_FPGA); @@ -339,7 +338,7 @@ double x300_impl::self_cal_adc_xfer_delay(mboard_members_t& mb, bool apply_delay                  err_code += 100;    //Increment error code by 100 to indicate no lock              }          } -        //UHD_MSG(status) << (boost::format("XferDelay=%fns, Error=%d\n") % delay % err_code); +        //UHD_LOGGER_INFO("X300") << (boost::format("XferDelay=%fns, Error=%d") % delay % err_code);          results.push_back(std::pair<double,bool>(delay, err_code==0));      } @@ -391,7 +390,6 @@ double x300_impl::self_cal_adc_xfer_delay(mboard_members_t& mb, bool apply_delay      }      if (apply_delay) { -        UHD_MSG(status) << "Validating..." << std::flush;          //Apply delay          win_center = mb.clock->set_clock_delay(X300_CLOCK_WHICH_ADC0, win_center);  //Sets ADC0 and ADC1          wait_for_clk_locked(mb, fw_regmap_t::clk_status_reg_t::LMK_LOCK, 0.1); @@ -407,7 +405,7 @@ double x300_impl::self_cal_adc_xfer_delay(mboard_members_t& mb, bool apply_delay          mb.radio_perifs[r].adc->set_test_word("normal", "normal");          mb.radio_perifs[r].regmap->misc_outs_reg.write(radio_regmap_t::misc_outs_reg_t::ADC_CHECKER_ENABLED, 0);      } -    UHD_MSG(status) << (boost::format(" done (FPGA->ADC=%.3fns%s, Window=%.3fns)\n") % +    UHD_LOGGER_INFO("X300") << (boost::format("ADC transfer delay self-cal done (FPGA->ADC=%.3fns%s, Window=%.3fns)") %          (win_center-fpga_clk_delay) % (cycle_slip?" +cyc":"") % win_length);      return win_center; diff --git a/host/lib/usrp/x300/x300_clock_ctrl.cpp b/host/lib/usrp/x300/x300_clock_ctrl.cpp index b8b100ceb..7307bcc66 100644 --- a/host/lib/usrp/x300/x300_clock_ctrl.cpp +++ b/host/lib/usrp/x300/x300_clock_ctrl.cpp @@ -303,9 +303,8 @@ public:              //be close to what the client requested.          } -        UHD_LOGV(often) -            << boost::format("x300_clock_ctrl::set_clock_delay: Which=%d, Requested=%f, Digital Taps=%d, Half Shift=%d, Analog Delay=%d (%s), Coerced Delay=%fns" -            ) % which % delay_ns % ddly_value % (half_shift_en?"ON":"OFF") % ((int)adly_value) % (adly_en?"ON":"OFF") % coerced_delay << std::endl; +        UHD_LOG_DEBUG("X300", boost::format("x300_clock_ctrl::set_clock_delay: Which=%d, Requested=%f, Digital Taps=%d, Half Shift=%d, Analog Delay=%d (%s), Coerced Delay=%fns" +                          ) % which % delay_ns % ddly_value % (half_shift_en?"ON":"OFF") % ((int)adly_value) % (adly_en?"ON":"OFF") % coerced_delay)          //Apply settings          switch (which) diff --git a/host/lib/usrp/x300/x300_dac_ctrl.cpp b/host/lib/usrp/x300/x300_dac_ctrl.cpp index 162eeb143..51b93662c 100644 --- a/host/lib/usrp/x300/x300_dac_ctrl.cpp +++ b/host/lib/usrp/x300/x300_dac_ctrl.cpp @@ -18,11 +18,10 @@  #include "x300_dac_ctrl.hpp"  #include "x300_regs.hpp"  #include <uhd/types/time_spec.hpp> -#include <uhd/utils/msg.hpp>  #include <uhd/utils/log.hpp>  #include <uhd/utils/safe_call.hpp>  #include <uhd/exception.hpp> -#include <boost/foreach.hpp> +#include <boost/format.hpp>  #include <boost/thread/thread.hpp> //sleep  #define X300_DAC_FRONTEND_SYNC_FAILURE_FATAL @@ -243,7 +242,7 @@ public:              if (failure_is_fatal) {                  throw uhd::runtime_error(msg);              } else { -                UHD_MSG(warning) << msg; +                UHD_LOGGER_WARNING("X300") << msg;              }          }      } diff --git a/host/lib/usrp/x300/x300_dboard_iface.cpp b/host/lib/usrp/x300/x300_dboard_iface.cpp index 092c888b0..e492fe2b3 100644 --- a/host/lib/usrp/x300/x300_dboard_iface.cpp +++ b/host/lib/usrp/x300/x300_dboard_iface.cpp @@ -34,7 +34,7 @@ x300_dboard_iface::x300_dboard_iface(const x300_dboard_iface_config_t &config):      //reset the aux dacs      _dac_regs[UNIT_RX] = ad5623_regs_t();      _dac_regs[UNIT_TX] = ad5623_regs_t(); -    BOOST_FOREACH(unit_t unit, _dac_regs.keys()) +    for(unit_t unit:  _dac_regs.keys())      {          _dac_regs[unit].data = 1;          _dac_regs[unit].addr = ad5623_regs_t::ADDR_ALL; diff --git a/host/lib/usrp/x300/x300_fw_ctrl.cpp b/host/lib/usrp/x300/x300_fw_ctrl.cpp index d149dadf3..5ff40c966 100644 --- a/host/lib/usrp/x300/x300_fw_ctrl.cpp +++ b/host/lib/usrp/x300/x300_fw_ctrl.cpp @@ -19,7 +19,7 @@  #include "x300_fw_common.h"  #include <uhd/transport/udp_simple.hpp>  #include <uhd/utils/byteswap.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/exception.hpp>  #include <boost/format.hpp>  #include <boost/thread/mutex.hpp> @@ -61,7 +61,7 @@ public:              {                  std::string error_msg = str(boost::format(                      "x300 fw communication failure #%u\n%s") % i % ex.what()); -                if (errors) UHD_MSG(error) << error_msg << std::endl; +                if (errors) UHD_LOGGER_ERROR("X300") << error_msg ;                  if (i == num_retries) throw uhd::io_error(error_msg);              }          } @@ -81,7 +81,7 @@ public:              {                  std::string error_msg = str(boost::format(                      "x300 fw communication failure #%u\n%s") % i % ex.what()); -                if (errors) UHD_MSG(error) << error_msg << std::endl; +                if (errors) UHD_LOGGER_ERROR("X300") << error_msg ;                  if (i == num_retries) throw uhd::io_error(error_msg);              }          } diff --git a/host/lib/usrp/x300/x300_fw_uart.cpp b/host/lib/usrp/x300/x300_fw_uart.cpp index a2cbcc908..83a564997 100644 --- a/host/lib/usrp/x300/x300_fw_uart.cpp +++ b/host/lib/usrp/x300/x300_fw_uart.cpp @@ -18,11 +18,10 @@  #include "x300_impl.hpp"  #include <uhd/types/wb_iface.hpp>  #include "x300_regs.hpp" -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/types/serial.hpp>  #include <uhd/exception.hpp>  #include <boost/format.hpp> -#include <boost/foreach.hpp>  #include <boost/thread/thread.hpp>  using namespace uhd; @@ -65,7 +64,7 @@ struct x300_uart_iface : uart_iface      void write_uart(const std::string &buff)      {          boost::mutex::scoped_lock(_write_mutex); -        BOOST_FOREACH(const char ch, buff) +        for(const char ch:  buff)          {              this->putchar(ch);          } diff --git a/host/lib/usrp/x300/x300_image_loader.cpp b/host/lib/usrp/x300/x300_image_loader.cpp index f08b21f9b..e8c2a1329 100644 --- a/host/lib/usrp/x300/x300_image_loader.cpp +++ b/host/lib/usrp/x300/x300_image_loader.cpp @@ -167,7 +167,7 @@ static void x300_setup_session(x300_session_t &session,          std::string err_msg = "Could not resolve given args to a single X-Series device.\n"                                "Applicable devices:\n"; -        BOOST_FOREACH(const uhd::device_addr_t &dev, devs){ +        for(const uhd::device_addr_t &dev:  devs){              std::string identifier = dev.has_key("addr") ? "addr"                                                           : "resource"; diff --git a/host/lib/usrp/x300/x300_impl.cpp b/host/lib/usrp/x300/x300_impl.cpp index 4f3870357..08865f9a6 100644 --- a/host/lib/usrp/x300/x300_impl.cpp +++ b/host/lib/usrp/x300/x300_impl.cpp @@ -23,12 +23,11 @@  #include <boost/algorithm/string.hpp>  #include <boost/asio.hpp>  #include <uhd/utils/static.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/paths.hpp>  #include <uhd/utils/safe_call.hpp>  #include <uhd/usrp/subdev_spec.hpp>  #include <uhd/transport/if_addrs.hpp> -#include <boost/foreach.hpp>  #include <boost/bind.hpp>  #include <boost/make_shared.hpp>  #include <boost/functional/hash.hpp> @@ -183,7 +182,7 @@ static device_addrs_t x300_find_pcie(const device_addr_t &hint, bool explicit_qu      nirio_status status = niusrprio_session::enumerate(rpc_port_name, dev_info_vtr);      if (explicit_query) nirio_status_to_exception(status, "x300_find_pcie: Error enumerating NI-RIO devices."); -    BOOST_FOREACH(niusrprio_session::device_info &dev_info, dev_info_vtr) +    for(niusrprio_session::device_info &dev_info:  dev_info_vtr)      {          device_addr_t new_addr;          new_addr["type"] = "x300"; @@ -278,7 +277,7 @@ device_addrs_t x300_find(const device_addr_t &hint_)      {          device_addrs_t found_devices;          std::string error_msg; -        BOOST_FOREACH(const device_addr_t &hint_i, hints) +        for(const device_addr_t &hint_i:  hints)          {              device_addrs_t found_devices_i = x300_find(hint_i);              if (found_devices_i.size() != 1) error_msg += str(boost::format( @@ -310,11 +309,11 @@ device_addrs_t x300_find(const device_addr_t &hint_)          }          catch(const std::exception &ex)          { -            UHD_MSG(error) << "X300 Network discovery error " << ex.what() << std::endl; +            UHD_LOGGER_ERROR("X300") << "X300 Network discovery error " << ex.what() ;          }          catch(...)          { -            UHD_MSG(error) << "X300 Network discovery unknown error " << std::endl; +            UHD_LOGGER_ERROR("X300") << "X300 Network discovery unknown error " ;          }          return reply_addrs;      } @@ -322,7 +321,7 @@ device_addrs_t x300_find(const device_addr_t &hint_)      if (!hint.has_key("resource"))      {          //otherwise, no address was specified, send a broadcast on each interface -        BOOST_FOREACH(const if_addrs_t &if_addrs, get_if_addrs()) +        for(const if_addrs_t &if_addrs:  get_if_addrs())          {              //avoid the loopback device              if (if_addrs.inet == asio::ip::address_v4::loopback().to_string()) continue; @@ -358,7 +357,7 @@ UHD_STATIC_BLOCK(register_x300_device)  static void x300_load_fw(wb_iface::sptr fw_reg_ctrl, const std::string &file_name)  { -    UHD_MSG(status) << "Loading firmware " << file_name << std::flush; +    UHD_LOGGER_INFO("X300") << "Loading firmware " << file_name;      //load file into memory      std::ifstream fw_file(file_name.c_str()); @@ -373,28 +372,52 @@ static void x300_load_fw(wb_iface::sptr fw_reg_ctrl, const std::string &file_nam          //@TODO: FIXME: Since x300_ctrl_iface acks each write and traps exceptions, the first try for the last word          //              written will print an error because it triggers a FW reload and fails to reply.          fw_reg_ctrl->poke32(SR_ADDR(BOOT_LDR_BASE, BL_DATA), uhd::byteswap(fw_file_buff[i/sizeof(uint32_t)])); -        if ((i & 0x1fff) == 0) UHD_MSG(status) << "." << std::flush;      }      //Wait for fimrware to reboot. 3s is an upper bound      boost::this_thread::sleep(boost::posix_time::milliseconds(3000)); -    UHD_MSG(status) << " done!" << std::endl; +    UHD_LOGGER_INFO("X300") << "Firmware loaded!" ;  } -x300_impl::x300_impl(const uhd::device_addr_t &dev_addr)  +x300_impl::x300_impl(const uhd::device_addr_t &dev_addr)      : device3_impl()      , _sid_framer(0)  { -    UHD_MSG(status) << "X300 initialization sequence..." << std::endl; +    UHD_LOGGER_INFO("X300") << "X300 initialization sequence...";      _ignore_cal_file = dev_addr.has_key("ignore-cal-file");      _tree->create<std::string>("/name").set("X-Series Device");      const device_addrs_t device_args = separate_device_addr(dev_addr);      _mb.resize(device_args.size()); -    for (size_t i = 0; i < device_args.size(); i++) + +    // Serialize the initialization process +    if (dev_addr.has_key("serialize_init") or device_args.size() == 1) { +        for (size_t i = 0; i < device_args.size(); i++) +        { +            this->setup_mb(i, device_args[i]); +        } +        return; +    } + + +    // Initialize groups of USRPs in parallel +    size_t total_usrps = device_args.size(); +    size_t num_usrps   = 0; +    while (num_usrps < total_usrps)      { -        this->setup_mb(i, device_args[i]); +        size_t init_usrps = std::min(total_usrps - num_usrps, X300_MAX_INIT_THREADS); +        boost::thread_group setup_threads; +        for (size_t i = 0; i < init_usrps; i++) +        { +            size_t index = num_usrps + i; +            setup_threads.create_thread( +                boost::bind(&x300_impl::setup_mb, this, index, device_args[index]) +            ); +        } +        setup_threads.join_all(); +        num_usrps += init_usrps;      } +  }  void x300_impl::mboard_members_t::discover_eth( @@ -412,15 +435,15 @@ void x300_impl::mboard_members_t::discover_eth(          // Show a warning if there exists duplicate addresses in the mboard eeprom          if (std::find(mb_eeprom_addrs.begin(), mb_eeprom_addrs.end(), mb_eeprom[key]) != mb_eeprom_addrs.end()) { -            UHD_MSG(warning) << str(boost::format( +            UHD_LOGGER_WARNING("X300") << str(boost::format(                  "Duplicate IP address %s found in mboard EEPROM. "                  "Device may not function properly.\nView and reprogram the values " -                "using the usrp_burn_mb_eeprom utility.\n") % mb_eeprom[key]); +                "using the usrp_burn_mb_eeprom utility.") % mb_eeprom[key]);          }          mb_eeprom_addrs.push_back(mb_eeprom[key]);      } -    BOOST_FOREACH(const std::string& addr, ip_addrs) { +    for(const std::string& addr:  ip_addrs) {          x300_eth_conn_t conn_iface;          conn_iface.addr = addr;          conn_iface.type = X300_IFACE_NONE; @@ -442,7 +465,7 @@ void x300_impl::mboard_members_t::discover_eth(          // Check default IP addresses if we couldn't          // determine the IP from the mboard eeprom          if (conn_iface.type == X300_IFACE_NONE) { -            UHD_MSG(warning) << str(boost::format( +            UHD_LOGGER_WARNING("X300") << str(boost::format(                  "Address %s not found in mboard EEPROM. Address may be wrong or "                  "the EEPROM may be corrupt.\n Attempting to continue with default "                  "IP addresses.\n") % conn_iface.addr @@ -505,6 +528,14 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)      mboard_members_t &mb = _mb[mb_i];      mb.initialization_done = false; +    const std::string thread_id( +        boost::lexical_cast<std::string>(boost::this_thread::get_id()) +    ); +    const std::string thread_msg( +        "Thread ID " + thread_id + " for motherboard " +        + boost::lexical_cast<std::string>(mb_i) +    ); +      std::vector<std::string> eth_addrs;      // Not choosing eth0 based on resource might cause user issues      std::string eth0_addr = dev_addr.has_key("resource") ? dev_addr["resource"] : dev_addr["addr"]; @@ -536,7 +567,7 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)          if (dev_addr.has_key("niusrpriorpc_port")) {              rpc_port_name = dev_addr["niusrpriorpc_port"];          } -        UHD_MSG(status) << boost::format("Connecting to niusrpriorpc at localhost:%s...\n") % rpc_port_name; +        UHD_LOGGER_INFO("X300") << boost::format("Connecting to niusrpriorpc at localhost:%s...") % rpc_port_name;          //Instantiate the correct lvbitx object          nifpga_lvbitx::sptr lvbitx; @@ -553,7 +584,7 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)                      drivers have loaded successfully.");          }          //Load the lvbitx onto the device -        UHD_MSG(status) << boost::format("Using LVBITX bitfile %s...\n") % lvbitx->get_bitfile_path(); +        UHD_LOGGER_INFO("X300") << boost::format("Using LVBITX bitfile %s...") % lvbitx->get_bitfile_path();          mb.rio_fpga_interface.reset(new niusrprio_session(dev_addr["resource"], rpc_port_name));          nirio_status_chain(mb.rio_fpga_interface->open(lvbitx, dev_addr.has_key("download-fpga")), status);          nirio_status_to_exception(status, "x300_impl: Could not initialize RIO session."); @@ -567,7 +598,7 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)          _tree->create<double>(mb_path / "link_max_rate").set(X300_MAX_RATE_PCIE);      } -    BOOST_FOREACH(const std::string &key, dev_addr.keys()) +    for(const std::string &key:  dev_addr.keys())      {          if (key.find("recv") != std::string::npos) mb.recv_args[key] = dev_addr[key];          if (key.find("send") != std::string::npos) mb.send_args[key] = dev_addr[key]; @@ -626,33 +657,33 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)                  );              }          } catch(std::exception &e) { -            UHD_MSG(error) << e.what() << std::endl; +            UHD_LOGGER_ERROR("X300") << e.what() ;          }          if ((mb.recv_args.has_key("recv_frame_size"))                  && (req_max_frame_size.recv_frame_size > _max_frame_sizes.recv_frame_size)) { -            UHD_MSG(warning) +            UHD_LOGGER_WARNING("X300")                  << boost::format("You requested a receive frame size of (%lu) but your NIC's max frame size is (%lu).")                  % req_max_frame_size.recv_frame_size                  % _max_frame_sizes.recv_frame_size -                << std::endl +                                  << boost::format("Please verify your NIC's MTU setting using '%s' or set the recv_frame_size argument appropriately.") -                % mtu_tool << std::endl +                % mtu_tool                   << "UHD will use the auto-detected max frame size for this connection." -                << std::endl; +                ;          }          if ((mb.recv_args.has_key("send_frame_size"))                  && (req_max_frame_size.send_frame_size > _max_frame_sizes.send_frame_size)) { -            UHD_MSG(warning) +            UHD_LOGGER_WARNING("X300")                  << boost::format("You requested a send frame size of (%lu) but your NIC's max frame size is (%lu).")                  % req_max_frame_size.send_frame_size                  % _max_frame_sizes.send_frame_size -                << std::endl +                                  << boost::format("Please verify your NIC's MTU setting using '%s' or set the send_frame_size argument appropriately.") -                % mtu_tool << std::endl +                % mtu_tool                   << "UHD will use the auto-detected max frame size for this connection." -                << std::endl; +                ;          }          _tree->create<size_t>(mb_path / "mtu/recv").set(_max_frame_sizes.recv_frame_size); @@ -661,7 +692,7 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)      }      //create basic communication -    UHD_MSG(status) << "Setup basic communication..." << std::endl; +    UHD_LOGGER_INFO("X300") << "Setup basic communication...";      if (mb.xport_path == "nirio") {          boost::mutex::scoped_lock(pcie_zpu_iface_registry_mutex);          if (get_pcie_zpu_iface_registry().has_key(mb.get_pri_eth().addr)) { @@ -721,11 +752,10 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)          const uint32_t nbor_addr = mb.zpu_ctrl->peek32(SR_ADDR(routes_addr, i*2+1));          if (node_addr != 0 and nbor_addr != 0)          { -            UHD_MSG(status) << boost::format("%u: %s -> %s") +            UHD_LOGGER_INFO("X300") << boost::format("%u: %s -> %s")                  % i                  % asio::ip::address_v4(node_addr).to_string() -                % asio::ip::address_v4(nbor_addr).to_string() -            << std::endl; +                % asio::ip::address_v4(nbor_addr).to_string();          }      }      */ @@ -733,11 +763,11 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)      ////////////////////////////////////////////////////////////////////      // setup the mboard eeprom      //////////////////////////////////////////////////////////////////// -    UHD_MSG(status) << "Loading values from EEPROM..." << std::endl; +    UHD_LOGGER_INFO("X300") << "Loading values from EEPROM...";      x300_mb_eeprom_iface::sptr eeprom16 = x300_mb_eeprom_iface::make(mb.zpu_ctrl, mb.zpu_i2c);      if (dev_addr.has_key("blank_eeprom"))      { -        UHD_MSG(warning) << "Obliterating the motherboard EEPROM..." << std::endl; +        UHD_LOGGER_WARNING("X300") << "Obliterating the motherboard EEPROM..." ;          eeprom16->write_eeprom(0x50, 0, byte_vector_t(256, 0xff));      }      const mboard_eeprom_t mb_eeprom(*eeprom16, "X300"); @@ -747,9 +777,9 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)      bool recover_mb_eeprom = dev_addr.has_key("recover_mb_eeprom");      if (recover_mb_eeprom) { -        UHD_MSG(warning) << "UHD is operating in EEPROM Recovery Mode which disables hardware version " +        UHD_LOGGER_WARNING("X300") << "UHD is operating in EEPROM Recovery Mode which disables hardware version "                              "checks.\nOperating in this mode may cause hardware damage and unstable " -                            "radio performance!"<< std::endl; +                            "radio performance!";      }      //////////////////////////////////////////////////////////////////// @@ -829,7 +859,7 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)      ////////////////////////////////////////////////////////////////////      // create clock control objects      //////////////////////////////////////////////////////////////////// -    UHD_MSG(status) << "Setup RF frontend clocking..." << std::endl; +    UHD_LOGGER_INFO("X300") << "Setup RF frontend clocking...";      //Initialize clock control registers. NOTE: This does not configure the LMK yet.      mb.clock = x300_clock_ctrl::make(mb.zpu_spi, @@ -851,8 +881,7 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)          .set_publisher(boost::bind(&x300_clock_ctrl::get_master_clock_rate, mb.clock))      ; -    UHD_MSG(status) << "Radio 1x clock:" << (mb.clock->get_master_clock_rate()/1e6) -        << std::endl; +    UHD_LOGGER_INFO("X300") << "Radio 1x clock:" << (mb.clock->get_master_clock_rate()/1e6);      ////////////////////////////////////////////////////////////////////      // Create the GPSDO control @@ -862,18 +891,18 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)      //otherwise if not disabled, look for the internal GPSDO      if (mb.zpu_ctrl->peek32(SR_ADDR(X300_FW_SHMEM_BASE, X300_FW_SHMEM_GPSDO_STATUS)) != dont_look_for_gpsdo)      { -        UHD_MSG(status) << "Detecting internal GPSDO.... " << std::flush; +        UHD_LOGGER_INFO("X300") << "Detecting internal GPSDO.... ";          try          {              mb.gps = gps_ctrl::make(x300_make_uart_iface(mb.zpu_ctrl));          }          catch(std::exception &e)          { -            UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl; +            UHD_LOGGER_ERROR("X300") << "An error occurred making GPSDO control: " << e.what() ;          }          if (mb.gps and mb.gps->gps_detected())          { -            BOOST_FOREACH(const std::string &name, mb.gps->get_sensors()) +            for(const std::string &name:  mb.gps->get_sensors())              {                  _tree->create<sensor_value_t>(mb_path / "sensors" / name)                      .set_publisher(boost::bind(&gps_ctrl::get_sensor, mb.gps, name)); @@ -886,14 +915,6 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)      }      //////////////////////////////////////////////////////////////////// -    //clear router? -    //////////////////////////////////////////////////////////////////// -    for (size_t i = 0; i < 512; i++) { -        mb.zpu_ctrl->poke32(SR_ADDR(SETXB_BASE, i), 0); -    } - - -    ////////////////////////////////////////////////////////////////////      // setup time sources and properties      ////////////////////////////////////////////////////////////////////      _tree->create<std::string>(mb_path / "time_source" / "value") @@ -950,8 +971,7 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)          n_rfnoc_blocks,          X300_XB_DST_PCI + 1, /* base port */          uhd::sid_t(X300_SRC_ADDR0, 0, X300_DST_ADDR + mb_i, 0), -        dev_addr, -        mb.if_pkt_is_big_endian ? ENDIANNESS_BIG : ENDIANNESS_LITTLE +        dev_addr      );      //////////////// RFNOC ///////////////// @@ -961,11 +981,11 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)                  find_blocks<rfnoc::x300_radio_ctrl_impl>(radio_blockid_hint);      if (not radio_ids.empty()) {          if (radio_ids.size() > 2) { -            UHD_MSG(warning) << "Too many Radio Blocks found. Using only the first two." << std::endl; +            UHD_LOGGER_WARNING("X300") << "Too many Radio Blocks found. Using only the first two." ;              radio_ids.resize(2);          } -        BOOST_FOREACH(const rfnoc::block_id_t &id, radio_ids) { +        for(const rfnoc::block_id_t &id:  radio_ids) {              rfnoc::x300_radio_ctrl_impl::sptr radio(get_block_ctrl<rfnoc::x300_radio_ctrl_impl>(id));              mb.radios.push_back(radio);              radio->setup_radio( @@ -1003,7 +1023,7 @@ void x300_impl::setup_mb(const size_t mb_i, const uhd::device_addr_t &dev_addr)          }      } else { -        UHD_MSG(status) << "No Radio Block found. Assuming radio-less operation." << std::endl; +        UHD_LOGGER_INFO("X300") << "No Radio Block found. Assuming radio-less operation.";      } /* end of radio block(s) initialization */      mb.initialization_done = true; @@ -1013,7 +1033,7 @@ x300_impl::~x300_impl(void)  {      try      { -        BOOST_FOREACH(mboard_members_t &mb, _mb) +        for(mboard_members_t &mb:  _mb)          {              //kill the claimer task and unclaim the device              mb.claimer_task.reset(); @@ -1046,8 +1066,8 @@ uint32_t x300_impl::mboard_members_t::allocate_pcie_dma_chan(const uhd::sid_t &t          if (_dma_chan_pool.count(raw_sid) == 0) {              _dma_chan_pool[raw_sid] = _dma_chan_pool.size() + FIRST_DATA_CHANNEL; -            UHD_LOG << "[X300] Assigning PCIe DMA channel " << _dma_chan_pool[raw_sid] -                            << " to SID " << tx_sid.to_pp_string_hex() << std::endl; +            UHD_LOGGER_DEBUG("X300") << "[X300] Assigning PCIe DMA channel " << _dma_chan_pool[raw_sid] +                            << " to SID " << tx_sid.to_pp_string_hex() ;          }          if (_dma_chan_pool.size() + FIRST_DATA_CHANNEL > X300_PCIE_MAX_CHANNELS) { @@ -1072,6 +1092,7 @@ uhd::both_xports_t x300_impl::make_transport(      zero_copy_xport_params default_buff_args;      both_xports_t xports; +    xports.endianness = mb.if_pkt_is_big_endian ? ENDIANNESS_BIG : ENDIANNESS_LITTLE;      if (mb.xport_path == "nirio") {          xports.send_sid = this->allocate_sid(mb, address, X300_SRC_ADDR0, X300_XB_DST_PCI);          xports.recv_sid = xports.send_sid.reversed(); @@ -1181,23 +1202,23 @@ uhd::both_xports_t x300_impl::make_transport(          /* Print a warning if the system's max available frame size is less than the most optimal           * frame size for this type of connection. */          if (_max_frame_sizes.send_frame_size < eth_data_rec_frame_size) { -            UHD_MSG(warning) +            UHD_LOGGER_WARNING("X300")                  << boost::format("For this connection, UHD recommends a send frame size of at least %lu for best\nperformance, but your system's MTU will only allow %lu.")                  % eth_data_rec_frame_size                  % _max_frame_sizes.send_frame_size -                << std::endl +                                  << "This will negatively impact your maximum achievable sample rate." -                << std::endl; +                ;          }          if (_max_frame_sizes.recv_frame_size < eth_data_rec_frame_size) { -            UHD_MSG(warning) +            UHD_LOGGER_WARNING("X300")                  << boost::format("For this connection, UHD recommends a receive frame size of at least %lu for best\nperformance, but your system's MTU will only allow %lu.")                  % eth_data_rec_frame_size                  % _max_frame_sizes.recv_frame_size -                << std::endl +                                  << "This will negatively impact your maximum achievable sample rate." -                << std::endl; +                ;          }          size_t system_max_send_frame_size = (size_t) _max_frame_sizes.send_frame_size; @@ -1255,8 +1276,8 @@ uhd::both_xports_t x300_impl::make_transport(          //send a mini packet with SID into the ZPU          //ZPU will reprogram the ethernet framer -        UHD_LOG << "programming packet for new xport on " -            << interface_addr <<  " sid " << xports.send_sid << std::endl; +        UHD_LOGGER_DEBUG("X300") << "programming packet for new xport on " +            << interface_addr <<  " sid " << xports.send_sid ;          //YES, get a __send__ buffer from the __recv__ socket          //-- this is the only way to program the framer for recv:          managed_send_buffer::sptr buff = xports.recv->get_send_buff(); @@ -1266,7 +1287,7 @@ uhd::both_xports_t x300_impl::make_transport(          buff.reset();          //reprogram the ethernet dispatcher's udp port (should be safe to always set) -        UHD_LOG << "reprogram the ethernet dispatcher's udp port" << std::endl; +        UHD_LOGGER_DEBUG("X300") << "reprogram the ethernet dispatcher's udp port" ;          mb.zpu_ctrl->poke32(SR_ADDR(SET0_BASE, (ZPU_SR_ETHINT0+8+3)), X300_VITA_UDP_PORT);          mb.zpu_ctrl->poke32(SR_ADDR(SET0_BASE, (ZPU_SR_ETHINT1+8+3)), X300_VITA_UDP_PORT); @@ -1286,7 +1307,7 @@ uhd::sid_t x300_impl::allocate_sid(  ) {      uhd::sid_t sid = address;      sid.set_src_addr(src_addr); -    sid.set_src_endpoint(_sid_framer); +    sid.set_src_endpoint(_sid_framer++);    //increment for next setup      // TODO Move all of this setup_mb()      // Program the X300 to recognise it's own local address. @@ -1298,10 +1319,7 @@ uhd::sid_t x300_impl::allocate_sid(      // This type of packet does not match the XB_LOCAL address and is looked up in the lower half of the CAM      mb.zpu_ctrl->poke32(SR_ADDR(SETXB_BASE, 0 + src_addr), src_dst); -    UHD_LOG << "done router config for sid " << sid << std::endl; - -    //increment for next setup -    _sid_framer++; +    UHD_LOGGER_TRACE("X300") << "done router config for sid " << sid ;      return sid;  } @@ -1355,8 +1373,8 @@ void x300_impl::update_clock_source(mboard_members_t &mb, const std::string &sou                  throw uhd::runtime_error((boost::format("Reference Clock PLL failed to lock to %s source.") % source).str());              } else {                  //TODO: Re-enable this warning when we figure out a reliable lock time -                //UHD_MSG(warning) << "Reference clock failed to lock to " + source + " during device initialization.  " << -                //    "Check for the lock before operation or ignore this warning if using another clock source." << std::endl; +                //UHD_LOGGER_WARNING("X300") << "Reference clock failed to lock to " + source + " during device initialization.  " << +                //    "Check for the lock before operation or ignore this warning if using another clock source." ;              }          }      } @@ -1381,7 +1399,7 @@ void x300_impl::update_clock_source(mboard_members_t &mb, const std::string &sou          }          // Reset ADCs and DACs -        BOOST_FOREACH(rfnoc::x300_radio_ctrl_impl::sptr r, mb.radios) { +        for(rfnoc::x300_radio_ctrl_impl::sptr r:  mb.radios) {              r->reset_codec();          }      } @@ -1413,7 +1431,7 @@ void x300_impl::update_time_source(mboard_members_t &mb, const std::string &sour  void x300_impl::sync_times(mboard_members_t &mb, const uhd::time_spec_t& t)  {      std::vector<rfnoc::block_id_t> radio_ids = find_blocks<rfnoc::x300_radio_ctrl_impl>("Radio"); -    BOOST_FOREACH(const rfnoc::block_id_t &id, radio_ids) { +    for(const rfnoc::block_id_t &id:  radio_ids) {          get_block_ctrl<rfnoc::x300_radio_ctrl_impl>(id)->set_time_sync(t);      } @@ -1574,7 +1592,7 @@ x300_impl::frame_size_t x300_impl::determine_max_frame_size(const std::string &a      size_t min_send_frame_size = sizeof(x300_mtu_t);      size_t max_send_frame_size = std::min(user_frame_size.send_frame_size, X300_10GE_DATA_FRAME_MAX_SIZE) & size_t(~3); -    UHD_MSG(status) << "Determining maximum frame size... "; +    UHD_LOGGER_INFO("X300") << "Determining maximum frame size... ";      while (min_recv_frame_size < max_recv_frame_size)      {         size_t test_frame_size = (max_recv_frame_size/2 + min_recv_frame_size/2 + 3) & ~3; @@ -1623,7 +1641,7 @@ x300_impl::frame_size_t x300_impl::determine_max_frame_size(const std::string &a      // of the recv and send frame sizes.      frame_size.recv_frame_size = std::min(min_recv_frame_size, min_send_frame_size);      frame_size.send_frame_size = std::min(min_recv_frame_size, min_send_frame_size); -    UHD_MSG(status) << frame_size.send_frame_size << " bytes." << std::endl; +    UHD_LOGGER_INFO("X300") << "Maximum frame size: " << frame_size.send_frame_size << " bytes.";      return frame_size;  } @@ -1800,7 +1818,7 @@ x300_impl::x300_mboard_t x300_impl::get_mb_type_from_eeprom(const uhd::usrp::mbo              case X310_2955R_PCIE_SSID_ADC_18:                  mb_type = USRP_X310_MB; break;              default: -                UHD_MSG(warning) << "X300 unknown product code in EEPROM: " << product_num << std::endl; +                UHD_LOGGER_WARNING("X300") << "X300 unknown product code in EEPROM: " << product_num ;                  mb_type = UNKNOWN;      break;          }      } diff --git a/host/lib/usrp/x300/x300_impl.hpp b/host/lib/usrp/x300/x300_impl.hpp index 14120bd1f..27f3f130e 100644 --- a/host/lib/usrp/x300/x300_impl.hpp +++ b/host/lib/usrp/x300/x300_impl.hpp @@ -39,6 +39,7 @@  #include <uhd/rfnoc/block_ctrl.hpp>  ///////////// RFNOC /////////////////////  #include <boost/dynamic_bitset.hpp> +#include <atomic>  static const std::string X300_FW_FILE_NAME  = "usrp_x300_fw.bin";  static const std::string X300_DEFAULT_CLOCK_SOURCE  = "internal"; @@ -76,6 +77,9 @@ static const size_t X300_ETH_MSG_NUM_FRAMES         = 64;  static const size_t X300_ETH_DATA_NUM_FRAMES        = 32;  static const double X300_DEFAULT_SYSREF_RATE        = 10e6; +// Limit the number of initialization threads +static const size_t X300_MAX_INIT_THREADS           = 10; +  static const size_t X300_MAX_RATE_PCIE              = 800000000; // bytes/s  static const size_t X300_MAX_RATE_10GIGE            = (size_t)(  // bytes/s          10e9 / 8 *                                               // wire speed multiplied by percentage of packets that is sample data @@ -215,7 +219,7 @@ private:      //task for periodically reclaiming the device from others      void claimer_loop(uhd::wb_iface::sptr); -    size_t _sid_framer; +    std::atomic<size_t> _sid_framer;      uhd::sid_t allocate_sid(          mboard_members_t &mb, @@ -286,9 +290,6 @@ private:      /// More IO stuff      uhd::device_addr_t get_tx_hints(size_t mb_index);      uhd::device_addr_t get_rx_hints(size_t mb_index); -    uhd::endianness_t get_transport_endianness(size_t mb_index) { -        return _mb[mb_index].if_pkt_is_big_endian ? uhd::ENDIANNESS_BIG : uhd::ENDIANNESS_LITTLE; -    };      void post_streamer_hooks(uhd::direction_t dir);  }; diff --git a/host/lib/usrp/x300/x300_io_impl.cpp b/host/lib/usrp/x300/x300_io_impl.cpp index 1584cee24..eeff4091f 100644 --- a/host/lib/usrp/x300/x300_io_impl.cpp +++ b/host/lib/usrp/x300/x300_io_impl.cpp @@ -25,8 +25,6 @@  #include <boost/bind.hpp>  #include <uhd/utils/tasks.hpp>  #include <uhd/utils/log.hpp> -#include <uhd/utils/msg.hpp> -#include <boost/foreach.hpp>  #include <boost/make_shared.hpp>  using namespace uhd; @@ -73,7 +71,7 @@ void x300_impl::post_streamer_hooks(direction_t dir)      // Loop through all tx streamers. Find all radios connected to one      // streamer. Sync those. -    BOOST_FOREACH(const boost::weak_ptr<uhd::tx_streamer> &streamer_w, _tx_streamers.vals()) { +    for(const boost::weak_ptr<uhd::tx_streamer> &streamer_w:  _tx_streamers.vals()) {          const boost::shared_ptr<sph::send_packet_streamer> streamer =              boost::dynamic_pointer_cast<sph::send_packet_streamer>(streamer_w.lock());          if (not streamer) { @@ -83,7 +81,7 @@ void x300_impl::post_streamer_hooks(direction_t dir)          std::vector<rfnoc::x300_radio_ctrl_impl::sptr> radio_ctrl_blks =              streamer->get_terminator()->find_downstream_node<rfnoc::x300_radio_ctrl_impl>();          try { -            //UHD_MSG(status) << "[X300] syncing " << radio_ctrl_blks.size() << " radios " << std::endl; +            //UHD_LOGGER_INFO("X300") << "[X300] syncing " << radio_ctrl_blks.size() << " radios " ;              rfnoc::x300_radio_ctrl_impl::synchronize_dacs(radio_ctrl_blks);          }          catch(const uhd::io_error &ex) { diff --git a/host/lib/usrp/x300/x300_mb_eeprom.cpp b/host/lib/usrp/x300/x300_mb_eeprom.cpp index e39b36af8..084685991 100644 --- a/host/lib/usrp/x300/x300_mb_eeprom.cpp +++ b/host/lib/usrp/x300/x300_mb_eeprom.cpp @@ -33,7 +33,7 @@  #include "x300_impl.hpp"  #include <uhd/exception.hpp>  #include <uhd/utils/platform.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/utils/byteswap.hpp>  #include <boost/thread.hpp> diff --git a/host/lib/usrp/x300/x300_radio_ctrl_impl.cpp b/host/lib/usrp/x300/x300_radio_ctrl_impl.cpp index 69eb51f55..daae309c3 100644 --- a/host/lib/usrp/x300/x300_radio_ctrl_impl.cpp +++ b/host/lib/usrp/x300/x300_radio_ctrl_impl.cpp @@ -22,7 +22,7 @@  #include "gpio_atr_3000.hpp"  #include "apply_corrections.hpp"  #include <uhd/usrp/dboard_eeprom.hpp> -#include <uhd/utils/msg.hpp> +#include <uhd/utils/log.hpp>  #include <uhd/usrp/dboard_iface.hpp>  #include <uhd/rfnoc/node_ctrl_base.hpp>  #include <uhd/transport/chdr.hpp> @@ -30,6 +30,7 @@  #include <boost/algorithm/string.hpp>  #include <boost/make_shared.hpp>  #include <boost/date_time/posix_time/posix_time_io.hpp> +#include <boost/assign/list_of.hpp>  using namespace uhd;  using namespace uhd::usrp; @@ -44,7 +45,7 @@ static const size_t IO_MASTER_RADIO = 0;  UHD_RFNOC_RADIO_BLOCK_CONSTRUCTOR(x300_radio_ctrl)      , _ignore_cal_file(false)  { -    UHD_RFNOC_BLOCK_TRACE() << "x300_radio_ctrl_impl::ctor() " << std::endl; +    UHD_RFNOC_BLOCK_TRACE() << "x300_radio_ctrl_impl::ctor() " ;      ////////////////////////////////////////////////////////////////////      // Set up basic info @@ -82,7 +83,7 @@ UHD_RFNOC_RADIO_BLOCK_CONSTRUCTOR(x300_radio_ctrl)      if (_radio_type==PRIMARY) {          _fp_gpio = gpio_atr::gpio_atr_3000::make(ctrl, regs::sr_addr(regs::FP_GPIO), regs::RB_FP_GPIO); -        BOOST_FOREACH(const gpio_atr::gpio_attr_map_t::value_type attr, gpio_atr::gpio_attr_map) { +        for(const gpio_atr::gpio_attr_map_t::value_type attr:  gpio_atr::gpio_attr_map) {              _tree->create<uint32_t>(fs_path("gpio") / "FP0" / attr.second)                  .set(0)                  .add_coerced_subscriber(boost::bind(&gpio_atr::gpio_atr_3000::set_gpio_attr, _fp_gpio, attr.first, _1)); @@ -149,7 +150,7 @@ x300_radio_ctrl_impl::~x300_radio_ctrl_impl()      _tree->remove(_root_path / "rx_fe_corrections");      _tree->remove(_root_path / "tx_fe_corrections");      if (_radio_type==PRIMARY) { -        BOOST_FOREACH(const gpio_atr::gpio_attr_map_t::value_type attr, gpio_atr::gpio_attr_map) { +        for(const gpio_atr::gpio_attr_map_t::value_type attr:  gpio_atr::gpio_attr_map) {              _tree->remove(fs_path("gpio") / "FP0" / attr.second);          }          _tree->remove(fs_path("gpio") / "FP0" / "READBACK"); @@ -171,7 +172,7 @@ double x300_radio_ctrl_impl::set_rate(double rate)  {      const double actual_rate = get_rate();      if (not uhd::math::frequencies_are_equal(rate, actual_rate)) { -        UHD_MSG(warning) << "[X300 Radio] Requesting invalid sampling rate from device: " << rate/1e6 << " MHz. Actual rate is: " << actual_rate/1e6 << " MHz." << std::endl; +        UHD_LOGGER_WARNING("X300 RADIO") << "Requesting invalid sampling rate from device: " << rate/1e6 << " MHz. Actual rate is: " << actual_rate/1e6 << " MHz." ;      }      // On X3x0, tick rate can't actually be changed at runtime      return actual_rate; @@ -228,6 +229,20 @@ double x300_radio_ctrl_impl::get_rx_frequency(const size_t chan)      ).get();  } +double x300_radio_ctrl_impl::set_rx_bandwidth(const double bandwidth, const size_t chan) +{ +    return _tree->access<double>( +        fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name / "bandwidth" / "value") +    ).set(bandwidth).get(); +} + +double x300_radio_ctrl_impl::get_rx_bandwidth(const size_t chan) +{ +    return _tree->access<double>( +        fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name / "bandwidth" / "value") +    ).get(); +} +  double x300_radio_ctrl_impl::set_tx_gain(const double gain, const size_t chan)  {      //TODO: This is extremely hacky! @@ -238,7 +253,7 @@ double x300_radio_ctrl_impl::set_tx_gain(const double gain, const size_t chan)          radio_ctrl_impl::set_tx_gain(actual_gain, chan);          return gain;      } else { -        UHD_MSG(warning) << "set_tx_gain: could not apply gain for this daughterboard."; +        UHD_LOGGER_WARNING("X300 RADIO") << "set_tx_gain: could not apply gain for this daughterboard.";          radio_ctrl_impl::set_tx_gain(0.0, chan);          return 0.0;      } @@ -254,19 +269,209 @@ double x300_radio_ctrl_impl::set_rx_gain(const double gain, const size_t chan)          radio_ctrl_impl::set_rx_gain(actual_gain, chan);          return gain;      } else { -        UHD_MSG(warning) << "set_rx_gain: could not apply gain for this daughterboard."; +        UHD_LOGGER_WARNING("X300 RADIO") << "set_rx_gain: could not apply gain for this daughterboard.";          radio_ctrl_impl::set_tx_gain(0.0, chan);          return 0.0;      }  } +std::vector<std::string> x300_radio_ctrl_impl::get_rx_lo_names(const size_t chan) +{ +    fs_path rx_fe_fe_root = fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name); + +    std::vector<std::string> lo_names; +    if (_tree->exists(rx_fe_fe_root / "los")) { +        for(const std::string &name:  _tree->list(rx_fe_fe_root / "los")) { +            lo_names.push_back(name); +        } +    } +    return lo_names; +} + +std::vector<std::string> x300_radio_ctrl_impl::get_rx_lo_sources(const std::string &name, const size_t chan) +{ +    fs_path rx_fe_fe_root = fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name); + +    if (_tree->exists(rx_fe_fe_root / "los")) { +        if (name == ALL_LOS) { +            if (_tree->exists(rx_fe_fe_root / "los" / ALL_LOS)) { +                //Special value ALL_LOS support atomically sets the source for all LOs +                return _tree->access< std::vector<std::string> >(rx_fe_fe_root / "los" / ALL_LOS / "source" / "options").get(); +            } else { +                return std::vector<std::string>(); +            } +        } else { +            if (_tree->exists(rx_fe_fe_root / "los")) { +                return _tree->access< std::vector<std::string> >(rx_fe_fe_root / "los" / name / "source" / "options").get(); +            } else { +                throw uhd::runtime_error("Could not find LO stage " + name); +            } +        } +    } else { +        // If the daughterboard doesn't expose it's LO(s) then it can only be internal +        return std::vector<std::string> (1, "internal"); +    } +} + +void x300_radio_ctrl_impl::set_rx_lo_source(const std::string &src, const std::string &name, const size_t chan) +{ +    fs_path rx_fe_fe_root = fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name); + +    if (_tree->exists(rx_fe_fe_root / "los")) { +        if (name == ALL_LOS) { +            if (_tree->exists(rx_fe_fe_root / "los" / ALL_LOS)) { +                //Special value ALL_LOS support atomically sets the source for all LOs +                _tree->access<std::string>(rx_fe_fe_root / "los" / ALL_LOS / "source" / "value").set(src); +            } else { +                for(const std::string &n:  _tree->list(rx_fe_fe_root / "los")) { +                    this->set_rx_lo_source(src, n, chan); +                } +            } +        } else { +            if (_tree->exists(rx_fe_fe_root / "los")) { +                _tree->access<std::string>(rx_fe_fe_root / "los" / name / "source" / "value").set(src); +            } else { +                throw uhd::runtime_error("Could not find LO stage " + name); +            } +        } +    } else { +        throw uhd::runtime_error("This device does not support manual configuration of LOs"); +    } +} + +const std::string x300_radio_ctrl_impl::get_rx_lo_source(const std::string &name, const size_t chan) +{ +    fs_path rx_fe_fe_root = fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name); + +    if (_tree->exists(rx_fe_fe_root / "los")) { +        if (name == ALL_LOS) { +            //Special value ALL_LOS support atomically sets the source for all LOs +            return _tree->access<std::string>(rx_fe_fe_root / "los" / ALL_LOS / "source" / "value").get(); +        } else { +            if (_tree->exists(rx_fe_fe_root / "los")) { +                return _tree->access<std::string>(rx_fe_fe_root / "los" / name / "source" / "value").get(); +            } else { +                throw uhd::runtime_error("Could not find LO stage " + name); +            } +        } +    } else { +        // If the daughterboard doesn't expose it's LO(s) then it can only be internal +        return "internal"; +    } +} + +void x300_radio_ctrl_impl::set_rx_lo_export_enabled(bool enabled, const std::string &name, const size_t chan) +{ +    fs_path rx_fe_fe_root = fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name); + +    if (_tree->exists(rx_fe_fe_root / "los")) { +        if (name == ALL_LOS) { +            if (_tree->exists(rx_fe_fe_root / "los" / ALL_LOS)) { +                //Special value ALL_LOS support atomically sets the source for all LOs +                _tree->access<bool>(rx_fe_fe_root / "los" / ALL_LOS / "export").set(enabled); +            } else { +                for(const std::string &n:  _tree->list(rx_fe_fe_root / "los")) { +                    this->set_rx_lo_export_enabled(enabled, n, chan); +                } +            } +        } else { +            if (_tree->exists(rx_fe_fe_root / "los")) { +                _tree->access<bool>(rx_fe_fe_root / "los" / name / "export").set(enabled); +            } else { +                throw uhd::runtime_error("Could not find LO stage " + name); +            } +        } +    } else { +        throw uhd::runtime_error("This device does not support manual configuration of LOs"); +    } +} + +bool x300_radio_ctrl_impl::get_rx_lo_export_enabled(const std::string &name, const size_t chan) +{ +    fs_path rx_fe_fe_root = fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name); + +    if (_tree->exists(rx_fe_fe_root / "los")) { +        if (name == ALL_LOS) { +            //Special value ALL_LOS support atomically sets the source for all LOs +            return _tree->access<bool>(rx_fe_fe_root / "los" / ALL_LOS / "export").get(); +        } else { +            if (_tree->exists(rx_fe_fe_root / "los")) { +                return _tree->access<bool>(rx_fe_fe_root / "los" / name / "export").get(); +            } else { +                throw uhd::runtime_error("Could not find LO stage " + name); +            } +        } +    } else { +        // If the daughterboard doesn't expose it's LO(s), assume it cannot export +        return false; +    } +} + +double x300_radio_ctrl_impl::set_rx_lo_freq(double freq, const std::string &name, const size_t chan) +{ +    fs_path rx_fe_fe_root = fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name); + +    if (_tree->exists(rx_fe_fe_root / "los")) { +        if (name == ALL_LOS) { +            throw uhd::runtime_error("LO frequency must be set for each stage individually"); +        } else { +            if (_tree->exists(rx_fe_fe_root / "los")) { +                _tree->access<double>(rx_fe_fe_root / "los" / name / "freq" / "value").set(freq); +                return _tree->access<double>(rx_fe_fe_root / "los" / name / "freq" / "value").get(); +            } else { +                throw uhd::runtime_error("Could not find LO stage " + name); +            } +        } +    } else { +        throw uhd::runtime_error("This device does not support manual configuration of LOs"); +    } +} + +double x300_radio_ctrl_impl::get_rx_lo_freq(const std::string &name, const size_t chan) +{ +    fs_path rx_fe_fe_root = fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name); + +    if (_tree->exists(rx_fe_fe_root / "los")) { +        if (name == ALL_LOS) { +            throw uhd::runtime_error("LO frequency must be retrieved for each stage individually"); +        } else { +            if (_tree->exists(rx_fe_fe_root / "los")) { +                return _tree->access<double>(rx_fe_fe_root / "los" / name / "freq" / "value").get(); +            } else { +                throw uhd::runtime_error("Could not find LO stage " + name); +            } +        } +    } else { +        // Return actual RF frequency if the daughterboard doesn't expose it's LO(s) +        return _tree->access<double>(rx_fe_fe_root / "freq" /" value").get(); +    } +} + +freq_range_t x300_radio_ctrl_impl::get_rx_lo_freq_range(const std::string &name, const size_t chan) +{ +    fs_path rx_fe_fe_root = fs_path("dboards" / _radio_slot / "rx_frontends" / _rx_fe_map.at(chan).db_fe_name); + +    if (_tree->exists(rx_fe_fe_root / "los")) { +        if (name == ALL_LOS) { +            throw uhd::runtime_error("LO frequency range must be retrieved for each stage individually"); +        } else { +            if (_tree->exists(rx_fe_fe_root / "los")) { +                return _tree->access<freq_range_t>(rx_fe_fe_root / "los" / name / "freq" / "range").get(); +            } else { +                throw uhd::runtime_error("Could not find LO stage " + name); +            } +        } +    } else { +        // Return the actual RF range if the daughterboard doesn't expose it's LO(s) +        return _tree->access<meta_range_t>(rx_fe_fe_root / "freq" / "range").get(); +    } +} +  template <typename map_type>  static size_t _get_chan_from_map(std::map<size_t, map_type> map, const std::string &fe)  { -    // TODO replace with 'auto' when possible -    typedef typename std::map<size_t, map_type>::iterator chan_iterator; -    for (chan_iterator it = map.begin(); it != map.end(); ++it) { +    for (auto it = map.begin(); it != map.end(); ++it) {          if (it->second.db_fe_name == fe) {              return it->first;          } @@ -318,6 +523,68 @@ double x300_radio_ctrl_impl::get_output_samp_rate(size_t chan)      return _rx_fe_map.at(chan).core->get_output_rate();  } +std::vector<std::string> x300_radio_ctrl_impl::get_gpio_banks() const +{ +    std::vector<std::string> banks = boost::assign::list_of("RX")("TX"); +    // These pairs are the same, but RXA/TXA are from pre-rfnoc era and are kept for backward compat: +    banks.push_back("RX"+_radio_slot); +    banks.push_back("TX"+_radio_slot); +    if (_fp_gpio) { +        banks.push_back("FP0"); +    } +    return banks; +} + +void x300_radio_ctrl_impl::set_gpio_attr( +        const std::string &bank, +        const std::string &attr, +        const uint32_t value, +        const uint32_t mask +) { +    if (bank == "FP0" and _fp_gpio) { +        const uint32_t current = _tree->access<uint32_t>(fs_path("gpio") / bank / attr).get(); +        const uint32_t new_value = (current & ~mask) | (value & mask); +        _tree->access<uint32_t>(fs_path("gpio") / bank / attr).set(new_value); +        return; +    } +    if (bank.size() > 2 and bank[1] == 'X') +    { +        const std::string name = bank.substr(2); +        const dboard_iface::unit_t unit = (bank[0] == 'R')? dboard_iface::UNIT_RX : dboard_iface::UNIT_TX; +        dboard_iface::sptr iface = _tree->access<dboard_iface::sptr>(fs_path("dboards") / name / "iface").get(); +        if (attr == "CTRL") iface->set_pin_ctrl(unit, uint16_t(value), uint16_t(mask)); +        if (attr == "DDR") iface->set_gpio_ddr(unit, uint16_t(value), uint16_t(mask)); +        if (attr == "OUT") iface->set_gpio_out(unit, uint16_t(value), uint16_t(mask)); +        if (attr == "ATR_0X") iface->set_atr_reg(unit, gpio_atr::ATR_REG_IDLE, uint16_t(value), uint16_t(mask)); +        if (attr == "ATR_RX") iface->set_atr_reg(unit, gpio_atr::ATR_REG_RX_ONLY, uint16_t(value), uint16_t(mask)); +        if (attr == "ATR_TX") iface->set_atr_reg(unit, gpio_atr::ATR_REG_TX_ONLY, uint16_t(value), uint16_t(mask)); +        if (attr == "ATR_XX") iface->set_atr_reg(unit, gpio_atr::ATR_REG_FULL_DUPLEX, uint16_t(value), uint16_t(mask)); +    } +} + +uint32_t x300_radio_ctrl_impl::get_gpio_attr( +        const std::string &bank, +        const std::string &attr +) { +    if (bank == "FP0" and _fp_gpio) { +        return uint32_t(_tree->access<uint64_t>(fs_path("gpio") / bank / attr).get()); +    } +    if (bank.size() > 2 and bank[1] == 'X') { +        const std::string name = bank.substr(2); +        const dboard_iface::unit_t unit = (bank[0] == 'R')? dboard_iface::UNIT_RX : dboard_iface::UNIT_TX; +        dboard_iface::sptr iface = _tree->access<dboard_iface::sptr>(fs_path("dboards") / name / "iface").get(); +        if (attr == "CTRL") return iface->get_pin_ctrl(unit); +        if (attr == "DDR") return iface->get_gpio_ddr(unit); +        if (attr == "OUT") return iface->get_gpio_out(unit); +        if (attr == "ATR_0X") return iface->get_atr_reg(unit, gpio_atr::ATR_REG_IDLE); +        if (attr == "ATR_RX") return iface->get_atr_reg(unit, gpio_atr::ATR_REG_RX_ONLY); +        if (attr == "ATR_TX") return iface->get_atr_reg(unit, gpio_atr::ATR_REG_TX_ONLY); +        if (attr == "ATR_XX") return iface->get_atr_reg(unit, gpio_atr::ATR_REG_FULL_DUPLEX); +        if (attr == "READBACK") return iface->read_gpio(unit); +    } +    return 0; +} +  /****************************************************************************   * Radio control and setup   ***************************************************************************/ @@ -380,7 +647,7 @@ void x300_radio_ctrl_impl::setup_radio(      );      size_t rx_chan = 0, tx_chan = 0; -    BOOST_FOREACH(const std::string& fe, _db_manager->get_rx_frontends()) { +    for(const std::string& fe:  _db_manager->get_rx_frontends()) {          if (rx_chan >= _get_num_radios()) {              break;          } @@ -393,7 +660,7 @@ void x300_radio_ctrl_impl::setup_radio(          _rx_fe_map[rx_chan].core->set_fe_connection(usrp::fe_connection_t(conn, if_freq));          rx_chan++;      } -    BOOST_FOREACH(const std::string& fe, _db_manager->get_tx_frontends()) { +    for(const std::string& fe:  _db_manager->get_tx_frontends()) {          if (tx_chan >= _get_num_radios()) {              break;          } @@ -555,31 +822,26 @@ void x300_radio_ctrl_impl::self_test_adc(uint32_t ramp_time_ms)  void x300_radio_ctrl_impl::extended_adc_test(const std::vector<x300_radio_ctrl_impl::sptr>& radios, double duration_s)  {      static const size_t SECS_PER_ITER = 5; -    UHD_MSG(status) << boost::format("Running Extended ADC Self-Test (Duration=%.0fs, %ds/iteration)...\n") +    UHD_LOGGER_INFO("X300 RADIO") << boost::format("Running Extended ADC Self-Test (Duration=%.0fs, %ds/iteration)...")          % duration_s % SECS_PER_ITER;      size_t num_iters = static_cast<size_t>(ceil(duration_s/SECS_PER_ITER));      size_t num_failures = 0;      for (size_t iter = 0; iter < num_iters; iter++) { -        //Print date and time -        boost::posix_time::time_facet *facet = new boost::posix_time::time_facet("%d-%b-%Y %H:%M:%S"); -        std::ostringstream time_strm; -        time_strm.imbue(std::locale(std::locale::classic(), facet)); -        time_strm << boost::posix_time::second_clock::local_time();          //Run self-test -        UHD_MSG(status) << boost::format("-- [%s] Iteration %06d... ") % time_strm.str() % (iter+1); +        UHD_LOGGER_INFO("X300 RADIO") << boost::format("Extended ADC Self-Test Iteration %06d... ") % (iter+1);          try {              for (size_t i = 0; i < radios.size(); i++) {                  radios[i]->self_test_adc((SECS_PER_ITER*1000)/radios.size());              } -            UHD_MSG(status) << "passed" << std::endl; +            UHD_LOGGER_INFO("X300 RADIO") << boost::format("Extended ADC Self-Test Iteration %06d passed ") % (iter+1);          } catch(std::exception &e) {              num_failures++; -            UHD_MSG(status) << e.what() << std::endl; +            UHD_LOGGER_ERROR("X300 RADIO") << e.what();          }      }      if (num_failures == 0) { -        UHD_MSG(status) << "Extended ADC Self-Test PASSED\n"; +        UHD_LOGGER_INFO("X300 RADIO") << "Extended ADC Self-Test PASSED";      } else {          throw uhd::runtime_error(                  (boost::format("Extended ADC Self-Test FAILED!!! (%d/%d failures)\n") % num_failures % num_iters).str()); @@ -639,7 +901,7 @@ double x300_radio_ctrl_impl::self_cal_adc_xfer_delay(      boost::function<void(double)> wait_for_clk_locked,      bool apply_delay)  { -    UHD_MSG(status) << "Running ADC transfer delay self-cal: " << std::flush; +    UHD_LOGGER_INFO("X300 RADIO") << "Running ADC transfer delay self-cal: ";      //Effective resolution of the self-cal.      static const size_t NUM_DELAY_STEPS = 100; @@ -649,7 +911,6 @@ double x300_radio_ctrl_impl::self_cal_adc_xfer_delay(      double delay_range = 2 * master_clk_period;      double delay_incr = delay_range / NUM_DELAY_STEPS; -    UHD_MSG(status) << "Measuring..." << std::flush;      double cached_clk_delay = clock->get_clock_delay(X300_CLOCK_WHICH_ADC0);      double fpga_clk_delay = clock->get_clock_delay(X300_CLOCK_WHICH_FPGA); @@ -695,7 +956,7 @@ double x300_radio_ctrl_impl::self_cal_adc_xfer_delay(                  err_code += 100;    //Increment error code by 100 to indicate no lock              }          } -        //UHD_MSG(status) << (boost::format("XferDelay=%fns, Error=%d\n") % delay % err_code); +        //UHD_LOGGER_INFO("X300 RADIO") << (boost::format("XferDelay=%fns, Error=%d") % delay % err_code);          results.push_back(std::pair<double,bool>(delay, err_code==0));      } @@ -747,7 +1008,6 @@ double x300_radio_ctrl_impl::self_cal_adc_xfer_delay(      }      if (apply_delay) { -        UHD_MSG(status) << "Validating..." << std::flush;          //Apply delay          win_center = clock->set_clock_delay(X300_CLOCK_WHICH_ADC0, win_center);  //Sets ADC0 and ADC1          wait_for_clk_locked(0.1); @@ -765,7 +1025,7 @@ double x300_radio_ctrl_impl::self_cal_adc_xfer_delay(          radios[r]->_adc->set_test_word("normal", "normal");          radios[r]->_regs->misc_outs_reg.write(radio_regmap_t::misc_outs_reg_t::ADC_CHECKER_ENABLED, 0);      } -    UHD_MSG(status) << (boost::format(" done (FPGA->ADC=%.3fns%s, Window=%.3fns)\n") % +    UHD_LOGGER_INFO("X300 RADIO") << (boost::format("ADC transfer delay self-cal done (FPGA->ADC=%.3fns%s, Window=%.3fns)") %          (win_center-fpga_clk_delay) % (cycle_slip?" +cyc":"") % win_length);      return win_center; @@ -789,7 +1049,7 @@ void x300_radio_ctrl_impl::_update_atr_leds(const std::string &rx_ant, const siz  void x300_radio_ctrl_impl::_self_cal_adc_capture_delay(bool print_status)  { -    if (print_status) UHD_MSG(status) << "Running ADC capture delay self-cal..." << std::flush; +    if (print_status) UHD_LOGGER_INFO("X300 RADIO") << "Running ADC capture delay self-cal...";      static const uint32_t NUM_DELAY_STEPS = 32;   //The IDELAYE2 element has 32 steps      static const uint32_t NUM_RETRIES     = 2;    //Retry self-cal if it fails in warmup situations @@ -813,8 +1073,8 @@ void x300_radio_ctrl_impl::_self_cal_adc_capture_delay(bool print_status)              //and count deviations from the expected value              _regs->misc_outs_reg.write(radio_regmap_t::misc_outs_reg_t::ADC_CHECKER_ENABLED, 0);              _regs->misc_outs_reg.write(radio_regmap_t::misc_outs_reg_t::ADC_CHECKER_ENABLED, 1); -            //10ms @ 200MHz = 2 million samples -            boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +            //5ms @ 200MHz = 1 million samples +            boost::this_thread::sleep(boost::posix_time::milliseconds(5));              if (_regs->misc_ins_reg.read(radio_regmap_t::misc_ins_reg_t::ADC_CHECKER0_I_LOCKED)) {                  err_code += _regs->misc_ins_reg.get(radio_regmap_t::misc_ins_reg_t::ADC_CHECKER0_I_ERROR);              } else { @@ -828,8 +1088,8 @@ void x300_radio_ctrl_impl::_self_cal_adc_capture_delay(bool print_status)              //and count deviations from the expected value              _regs->misc_outs_reg.write(radio_regmap_t::misc_outs_reg_t::ADC_CHECKER_ENABLED, 0);              _regs->misc_outs_reg.write(radio_regmap_t::misc_outs_reg_t::ADC_CHECKER_ENABLED, 1); -            //10ms @ 200MHz = 2 million samples -            boost::this_thread::sleep(boost::posix_time::milliseconds(10)); +            //5ms @ 200MHz = 1 million samples +            boost::this_thread::sleep(boost::posix_time::milliseconds(5));              if (_regs->misc_ins_reg.read(radio_regmap_t::misc_ins_reg_t::ADC_CHECKER0_Q_LOCKED)) {                  err_code += _regs->misc_ins_reg.get(radio_regmap_t::misc_ins_reg_t::ADC_CHECKER0_Q_ERROR);              } else { @@ -852,7 +1112,7 @@ void x300_radio_ctrl_impl::_self_cal_adc_capture_delay(bool print_status)                      }                  }              } -            //UHD_MSG(status) << (boost::format("CapTap=%d, Error=%d\n") % dly_tap % err_code); +            //UHD_LOGGER_INFO("X300 RADIO") << (boost::format("CapTap=%d, Error=%d") % dly_tap % err_code);          }          //Retry the self-cal if it fails @@ -882,7 +1142,7 @@ void x300_radio_ctrl_impl::_self_cal_adc_capture_delay(bool print_status)      if (print_status) {          double tap_delay = (1.0e12 / _radio_clk_rate) / (2*32); //in ps -        UHD_MSG(status) << boost::format(" done (Tap=%d, Window=%d, TapDelay=%.3fps, Iter=%d)\n") % ideal_tap % (win_stop-win_start) % tap_delay % iter; +        UHD_LOGGER_INFO("X300 RADIO") << boost::format("ADC capture delay self-cal done (Tap=%d, Window=%d, TapDelay=%.3fps, Iter=%d)") % ideal_tap % (win_stop-win_start) % tap_delay % iter;      }  } @@ -916,7 +1176,7 @@ void x300_radio_ctrl_impl::_set_command_time(const time_spec_t &spec, const size   ***************************************************************************/  bool x300_radio_ctrl_impl::check_radio_config()  { -    UHD_RFNOC_BLOCK_TRACE() << "x300_radio_ctrl_impl::check_radio_config() " << std::endl; +    UHD_RFNOC_BLOCK_TRACE() << "x300_radio_ctrl_impl::check_radio_config() " ;      const fs_path rx_fe_path = fs_path("dboards" / _radio_slot / "rx_frontends");      for (size_t chan = 0; chan < _get_num_radios(); chan++) {          if (_tree->exists(rx_fe_path / _rx_fe_map.at(chan).db_fe_name / "enabled")) { diff --git a/host/lib/usrp/x300/x300_radio_ctrl_impl.hpp b/host/lib/usrp/x300/x300_radio_ctrl_impl.hpp index 417c88f9e..9e3f298d8 100644 --- a/host/lib/usrp/x300/x300_radio_ctrl_impl.hpp +++ b/host/lib/usrp/x300/x300_radio_ctrl_impl.hpp @@ -56,15 +56,34 @@ public:      double set_tx_frequency(const double freq, const size_t chan);      double set_rx_frequency(const double freq, const size_t chan); +    double set_rx_bandwidth(const double bandwidth, const size_t chan);      double get_tx_frequency(const size_t chan);      double get_rx_frequency(const size_t chan); +    double get_rx_bandwidth(const size_t chan);      double set_tx_gain(const double gain, const size_t chan);      double set_rx_gain(const double gain, const size_t chan); +    std::vector<std::string> get_rx_lo_names(const size_t chan); +    std::vector<std::string> get_rx_lo_sources(const std::string &name, const size_t chan); +    freq_range_t get_rx_lo_freq_range(const std::string &name, const size_t chan); + +    void set_rx_lo_source(const std::string &src, const std::string &name, const size_t chan); +    const std::string get_rx_lo_source(const std::string &name, const size_t chan); + +    void set_rx_lo_export_enabled(bool enabled, const std::string &name, const size_t chan); +    bool get_rx_lo_export_enabled(const std::string &name, const size_t chan); + +    double set_rx_lo_freq(double freq, const std::string &name, const size_t chan); +    double get_rx_lo_freq(const std::string &name, const size_t chan); +      size_t get_chan_from_dboard_fe(const std::string &fe, const direction_t dir);      std::string get_dboard_fe_from_chan(const size_t chan, const direction_t dir); +    std::vector<std::string> get_gpio_banks() const; +    void set_gpio_attr(const std::string &bank, const std::string &attr, const uint32_t value, const uint32_t mask); +    uint32_t get_gpio_attr(const std::string &bank, const std::string &attr); +      double get_output_samp_rate(size_t port);      /************************************************************************  | 
