diff options
Diffstat (limited to 'host/lib/usrp/usrp1')
| -rw-r--r-- | host/lib/usrp/usrp1/codec_ctrl.cpp | 26 | ||||
| -rw-r--r-- | host/lib/usrp/usrp1/io_impl.cpp | 33 | ||||
| -rw-r--r-- | host/lib/usrp/usrp1/soft_time_ctrl.cpp | 5 | ||||
| -rw-r--r-- | host/lib/usrp/usrp1/usrp1_calc_mux.hpp | 6 | ||||
| -rw-r--r-- | host/lib/usrp/usrp1/usrp1_iface.cpp | 20 | ||||
| -rw-r--r-- | host/lib/usrp/usrp1/usrp1_impl.cpp | 46 | ||||
| -rw-r--r-- | host/lib/usrp/usrp1/usrp1_impl.hpp | 6 | 
7 files changed, 73 insertions, 69 deletions
| 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..7cb38548f 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> @@ -32,6 +32,7 @@  #include <boost/bind.hpp>  #include <boost/format.hpp>  #include <boost/make_shared.hpp> +#include <atomic>  #define bmFR_RX_FORMAT_SHIFT_SHIFT 0  #define bmFR_RX_FORMAT_WIDTH_SHIFT 4 @@ -147,12 +148,14 @@ struct usrp1_impl::io_impl{      io_impl(zero_copy_if::sptr data_transport):          data_transport(data_transport),          curr_buff(offset_send_buffer(data_transport->get_send_buff())), -        omsb(boost::bind(&usrp1_impl::io_impl::commit_send_buff, this, _1, _2, _3)) +        omsb(boost::bind(&usrp1_impl::io_impl::commit_send_buff, this, _1, _2, _3)), +        vandal_loop_exit(false)      {          /* NOP */      }      ~io_impl(void){ +        vandal_loop_exit = true;          UHD_SAFE_CALL(flush_send_buff();)      } @@ -175,6 +178,7 @@ struct usrp1_impl::io_impl{          return omsb.get_new(curr_buff, next_buff);      } +    std::atomic<bool> vandal_loop_exit;      task::sptr vandal_task;      boost::system_time last_send_time;  }; @@ -247,7 +251,7 @@ void usrp1_impl::io_init(void){      //create a new vandal thread to poll xerflow conditions      _io_impl->vandal_task = task::make(boost::bind( -        &usrp1_impl::vandal_conquest_loop, this +        &usrp1_impl::vandal_conquest_loop, this, std::ref(_io_impl->vandal_loop_exit)      ));  } @@ -271,7 +275,7 @@ void usrp1_impl::tx_stream_on_off(bool enb){   * On an overflow, interleave an inline message into recv and print.   * This procedure creates "soft" inline and async user messages.   */ -void usrp1_impl::vandal_conquest_loop(void){ +void usrp1_impl::vandal_conquest_loop(std::atomic<bool> &exit_loop){      //initialize the async metadata      async_metadata_t async_metadata; @@ -285,7 +289,7 @@ void usrp1_impl::vandal_conquest_loop(void){      inline_metadata.error_code = rx_metadata_t::ERROR_CODE_OVERFLOW;      //start the polling loop... -    try{ while (not boost::this_thread::interruption_requested()){ +    try{ while (not exit_loop){          uint8_t underflow = 0, overflow = 0;          //shutoff transmit if it has been too long since send() was called @@ -305,19 +309,18 @@ 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 +442,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 +462,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 +503,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 +551,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/soft_time_ctrl.cpp b/host/lib/usrp/usrp1/soft_time_ctrl.cpp index bb8b3a704..9cef99a60 100644 --- a/host/lib/usrp/usrp1/soft_time_ctrl.cpp +++ b/host/lib/usrp/usrp1/soft_time_ctrl.cpp @@ -199,8 +199,9 @@ public:      void recv_cmd_task(void){ //task is looped          boost::shared_ptr<stream_cmd_t> cmd; -        _cmd_queue.pop_with_wait(cmd); -        recv_cmd_handle_cmd(*cmd); +        if (_cmd_queue.pop_with_timed_wait(cmd, 0.25)) { +            recv_cmd_handle_cmd(*cmd); +        }      }      bounded_buffer<async_metadata_t> &get_async_queue(void){ 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..92b7f5331 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()       ;      //////////////////////////////////////////////////////////////////// @@ -229,21 +229,21 @@ usrp1_impl::usrp1_impl(const device_addr_t &device_addr){      _master_clock_rate = 64e6;      if (device_addr.has_key("mcr")){          try{ -            _master_clock_rate = boost::lexical_cast<double>(device_addr["mcr"]); +            _master_clock_rate = std::stod(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()){          try{ -            _master_clock_rate = boost::lexical_cast<double>(mb_eeprom["mcr"]); +            _master_clock_rate = std::stod(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..b45d138d1 100644 --- a/host/lib/usrp/usrp1/usrp1_impl.hpp +++ b/host/lib/usrp/usrp1/usrp1_impl.hpp @@ -31,9 +31,9 @@  #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> +#include <atomic>  #ifndef INCLUDED_USRP1_IMPL_HPP  #define INCLUDED_USRP1_IMPL_HPP @@ -145,7 +145,7 @@ private:      bool has_rx_halfband(void);      bool has_tx_halfband(void); -    void vandal_conquest_loop(void); +    void vandal_conquest_loop(std::atomic<bool> &);      void set_reg(const std::pair<uint8_t, uint32_t> ®); @@ -158,7 +158,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);          } | 
