From 1526889803f2fc909d97c16b59323107db184381 Mon Sep 17 00:00:00 2001
From: Josh Blum <josh@joshknows.com>
Date: Thu, 24 Feb 2011 17:28:10 -0800
Subject: uhd: switch algorithm namespace to uhd

---
 host/lib/device.cpp                    |  2 +-
 host/lib/usrp/dboard/db_dbsrx.cpp      | 16 ++++++++--------
 host/lib/usrp/dboard/db_dbsrx2.cpp     | 12 ++++++------
 host/lib/usrp/dboard/db_rfx.cpp        |  2 +-
 host/lib/usrp/dboard/db_tvrx.cpp       |  6 +++---
 host/lib/usrp/dboard/db_xcvr2450.cpp   | 14 +++++++-------
 host/lib/usrp/misc_utils.cpp           |  2 +-
 host/lib/usrp/usrp1/codec_ctrl.cpp     |  8 ++++----
 host/lib/usrp/usrp_e100/codec_ctrl.cpp |  8 ++++----
 host/lib/utils/gain_group.cpp          |  6 +++---
 10 files changed, 38 insertions(+), 38 deletions(-)

(limited to 'host/lib')

diff --git a/host/lib/device.cpp b/host/lib/device.cpp
index ad37743c1..0002bee6e 100644
--- a/host/lib/device.cpp
+++ b/host/lib/device.cpp
@@ -43,7 +43,7 @@ static size_t hash_device_addr(
 ){
     //combine the hashes of sorted keys/value pairs
     size_t hash = 0;
-    BOOST_FOREACH(const std::string &key, std::sorted(dev_addr.keys())){
+    BOOST_FOREACH(const std::string &key, uhd::sorted(dev_addr.keys())){
         boost::hash_combine(hash, key);
         boost::hash_combine(hash, dev_addr[key]);
     }
diff --git a/host/lib/usrp/dboard/db_dbsrx.cpp b/host/lib/usrp/dboard/db_dbsrx.cpp
index 200822841..b984608ca 100644
--- a/host/lib/usrp/dboard/db_dbsrx.cpp
+++ b/host/lib/usrp/dboard/db_dbsrx.cpp
@@ -83,8 +83,8 @@ private:
     void set_bandwidth(double bandwidth);
 
     void send_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg){
-        start_reg = boost::uint8_t(std::clip(int(start_reg), 0x0, 0x5));
-        stop_reg = boost::uint8_t(std::clip(int(stop_reg), 0x0, 0x5));
+        start_reg = boost::uint8_t(uhd::clip(int(start_reg), 0x0, 0x5));
+        stop_reg = boost::uint8_t(uhd::clip(int(stop_reg), 0x0, 0x5));
 
         for(boost::uint8_t start_addr=start_reg; start_addr <= stop_reg; start_addr += sizeof(boost::uint32_t) - 1){
             int num_bytes = int(stop_reg - start_addr + 1) > int(sizeof(boost::uint32_t)) - 1 ? sizeof(boost::uint32_t) - 1 : stop_reg - start_addr + 1;
@@ -112,8 +112,8 @@ private:
 
     void read_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg){
         static const boost::uint8_t status_addr = 0x0;
-        start_reg = boost::uint8_t(std::clip(int(start_reg), 0x0, 0x1));
-        stop_reg = boost::uint8_t(std::clip(int(stop_reg), 0x0, 0x1));
+        start_reg = boost::uint8_t(uhd::clip(int(start_reg), 0x0, 0x1));
+        stop_reg = boost::uint8_t(uhd::clip(int(stop_reg), 0x0, 0x1));
 
         for(boost::uint8_t start_addr=start_reg; start_addr <= stop_reg; start_addr += sizeof(boost::uint32_t)){
             int num_bytes = int(stop_reg - start_addr + 1) > int(sizeof(boost::uint32_t)) ? sizeof(boost::uint32_t) : stop_reg - start_addr + 1;
@@ -237,8 +237,8 @@ void dbsrx::set_lo_freq(double target_freq){
     bool update_filter_settings = false;
     //choose refclock
     std::vector<double> clock_rates = this->get_iface()->get_clock_rates(dboard_iface::UNIT_RX);
-    const double max_clock_rate = std::sorted(clock_rates).back();
-    BOOST_FOREACH(ref_clock, std::reversed(std::sorted(clock_rates))){
+    const double max_clock_rate = uhd::sorted(clock_rates).back();
+    BOOST_FOREACH(ref_clock, uhd::reversed(uhd::sorted(clock_rates))){
         if (ref_clock > 27.0e6) continue;
         if (size_t(max_clock_rate/ref_clock)%2 == 1) continue; //reject asymmetric clocks (odd divisors)
 
@@ -485,14 +485,14 @@ void dbsrx::set_gain(double gain, const std::string &name){
  **********************************************************************/
 void dbsrx::set_bandwidth(double bandwidth){
     //clip the input
-    bandwidth = std::clip<double>(bandwidth, 4e6, 33e6);
+    bandwidth = uhd::clip<double>(bandwidth, 4e6, 33e6);
 
     double ref_clock = this->get_iface()->get_clock_rate(dboard_iface::UNIT_RX);
     
     //NOTE: _max2118_write_regs.m_divider set in set_lo_freq
 
     //compute f_dac setting
-    _max2118_write_regs.f_dac = std::clip<int>(int((((bandwidth*_max2118_write_regs.m_divider)/ref_clock) - 4)/0.145),0,127);
+    _max2118_write_regs.f_dac = uhd::clip<int>(int((((bandwidth*_max2118_write_regs.m_divider)/ref_clock) - 4)/0.145),0,127);
 
     //determine actual bandwidth
     _bandwidth = double((ref_clock/(_max2118_write_regs.m_divider))*(4+0.145*_max2118_write_regs.f_dac));
diff --git a/host/lib/usrp/dboard/db_dbsrx2.cpp b/host/lib/usrp/dboard/db_dbsrx2.cpp
index dd97f76b1..e7b42cb05 100644
--- a/host/lib/usrp/dboard/db_dbsrx2.cpp
+++ b/host/lib/usrp/dboard/db_dbsrx2.cpp
@@ -79,8 +79,8 @@ private:
     void set_bandwidth(double bandwidth);
 
     void send_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg){
-        start_reg = boost::uint8_t(std::clip(int(start_reg), 0x0, 0xB));
-        stop_reg = boost::uint8_t(std::clip(int(stop_reg), 0x0, 0xB));
+        start_reg = boost::uint8_t(uhd::clip(int(start_reg), 0x0, 0xB));
+        stop_reg = boost::uint8_t(uhd::clip(int(stop_reg), 0x0, 0xB));
 
         for(boost::uint8_t start_addr=start_reg; start_addr <= stop_reg; start_addr += sizeof(boost::uint32_t) - 1){
             int num_bytes = int(stop_reg - start_addr + 1) > int(sizeof(boost::uint32_t)) - 1 ? sizeof(boost::uint32_t) - 1 : stop_reg - start_addr + 1;
@@ -108,8 +108,8 @@ private:
 
     void read_reg(boost::uint8_t start_reg, boost::uint8_t stop_reg){
         static const boost::uint8_t status_addr = 0xC;
-        start_reg = boost::uint8_t(std::clip(int(start_reg), 0x0, 0xD));
-        stop_reg = boost::uint8_t(std::clip(int(stop_reg), 0x0, 0xD));
+        start_reg = boost::uint8_t(uhd::clip(int(start_reg), 0x0, 0xD));
+        stop_reg = boost::uint8_t(uhd::clip(int(stop_reg), 0x0, 0xD));
 
         for(boost::uint8_t start_addr=start_reg; start_addr <= stop_reg; start_addr += sizeof(boost::uint32_t)){
             int num_bytes = int(stop_reg - start_addr + 1) > int(sizeof(boost::uint32_t)) ? sizeof(boost::uint32_t) : stop_reg - start_addr + 1;
@@ -216,7 +216,7 @@ dbsrx2::~dbsrx2(void){
  * Tuning
  **********************************************************************/
 void dbsrx2::set_lo_freq(double target_freq){
-    //target_freq = std::clip(target_freq, dbsrx2_freq_range.min, dbsrx2_freq_range.max);
+    //target_freq = uhd::clip(target_freq, dbsrx2_freq_range.min, dbsrx2_freq_range.max);
 
     //variables used in the calculation below
     int scaler = target_freq > 1125e6 ? 2 : 4;
@@ -330,7 +330,7 @@ void dbsrx2::set_gain(double gain, const std::string &name){
  **********************************************************************/
 void dbsrx2::set_bandwidth(double bandwidth){
     //clip the input
-    bandwidth = std::clip<double>(bandwidth, 4e6, 40e6);
+    bandwidth = uhd::clip<double>(bandwidth, 4e6, 40e6);
 
     _max2112_write_regs.lp = int((bandwidth/1e6 - 4)/0.29 + 12);
     _bandwidth = double(4 + (_max2112_write_regs.lp - 12) * 0.29)*1e6;
diff --git a/host/lib/usrp/dboard/db_rfx.cpp b/host/lib/usrp/dboard/db_rfx.cpp
index 5e269fc64..4d8222a52 100644
--- a/host/lib/usrp/dboard/db_rfx.cpp
+++ b/host/lib/usrp/dboard/db_rfx.cpp
@@ -245,7 +245,7 @@ static double rx_pga0_gain_to_dac_volts(double &gain, double range){
     static const double slope = (max_volts-min_volts)/(range);
 
     //calculate the voltage for the aux dac
-    double dac_volts = std::clip<double>(gain*slope + min_volts, max_volts, min_volts);
+    double dac_volts = uhd::clip<double>(gain*slope + min_volts, max_volts, min_volts);
 
     //the actual gain setting
     gain = (dac_volts - min_volts)/slope;
diff --git a/host/lib/usrp/dboard/db_tvrx.cpp b/host/lib/usrp/dboard/db_tvrx.cpp
index 4d7cb22f8..dc38ef45e 100644
--- a/host/lib/usrp/dboard/db_tvrx.cpp
+++ b/host/lib/usrp/dboard/db_tvrx.cpp
@@ -241,7 +241,7 @@ static std::string get_band(double freq) {
 
 static double gain_interp(double gain, boost::array<double, 17> db_vector, boost::array<double, 17> volts_vector) {
     double volts;
-    gain = std::clip<double>(gain, db_vector.front(), db_vector.back()); //let's not get carried away here
+    gain = uhd::clip<double>(gain, db_vector.front(), db_vector.back()); //let's not get carried away here
 
     boost::uint8_t gain_step = 0;
     //find which bin we're in
@@ -288,7 +288,7 @@ static double rf_gain_to_voltage(double gain, double lo_freq){
     //this is the voltage at the USRP DAC output
     double dac_volts = gain_volts / opamp_gain;
 
-    dac_volts = std::clip<double>(dac_volts, 0.0, 3.3);
+    dac_volts = uhd::clip<double>(dac_volts, 0.0, 3.3);
 
     if (tvrx_debug) std::cerr << boost::format(
         "tvrx RF AGC gain: %f dB, dac_volts: %f V"
@@ -311,7 +311,7 @@ static double if_gain_to_voltage(double gain){
     double gain_volts = gain_interp(gain, tvrx_if_gains_db, tvrx_gains_volts);
     double dac_volts = gain_volts / opamp_gain;
 
-    dac_volts = std::clip<double>(dac_volts, 0.0, 3.3);
+    dac_volts = uhd::clip<double>(dac_volts, 0.0, 3.3);
 
     if (tvrx_debug) std::cerr << boost::format(
         "tvrx IF AGC gain: %f dB, dac_volts: %f V"
diff --git a/host/lib/usrp/dboard/db_xcvr2450.cpp b/host/lib/usrp/dboard/db_xcvr2450.cpp
index 4eafd6fda..9d25b30a5 100644
--- a/host/lib/usrp/dboard/db_xcvr2450.cpp
+++ b/host/lib/usrp/dboard/db_xcvr2450.cpp
@@ -358,7 +358,7 @@ void xcvr2450::set_rx_ant(const std::string &ant){
  */
 static int gain_to_tx_vga_reg(double &gain){
     //calculate the register value
-    int reg = std::clip(boost::math::iround(gain*60/30.0) + 3, 0, 63);
+    int reg = uhd::clip(boost::math::iround(gain*60/30.0) + 3, 0, 63);
 
     //calculate the actual gain value
     if (reg < 4)       gain = 0;
@@ -376,7 +376,7 @@ static int gain_to_tx_vga_reg(double &gain){
  * \return gain enum value
  */
 static max2829_regs_t::tx_baseband_gain_t gain_to_tx_bb_reg(double &gain){
-    int reg = std::clip(boost::math::iround(gain*3/5.0), 0, 3);
+    int reg = uhd::clip(boost::math::iround(gain*3/5.0), 0, 3);
     switch(reg){
     case 0:
         gain = 0;
@@ -401,7 +401,7 @@ static max2829_regs_t::tx_baseband_gain_t gain_to_tx_bb_reg(double &gain){
  * \return 5 bit the register value
  */
 static int gain_to_rx_vga_reg(double &gain){
-    int reg = std::clip(boost::math::iround(gain/2.0), 0, 31);
+    int reg = uhd::clip(boost::math::iround(gain/2.0), 0, 31);
     gain = double(reg*2);
     return reg;
 }
@@ -413,7 +413,7 @@ static int gain_to_rx_vga_reg(double &gain){
  * \return 2 bit the register value
  */
 static int gain_to_rx_lna_reg(double &gain){
-    int reg = std::clip(boost::math::iround(gain*2/30.5) + 1, 0, 3);
+    int reg = uhd::clip(boost::math::iround(gain*2/30.5) + 1, 0, 3);
     switch(reg){
     case 0:
     case 1: gain = 0;    break;
@@ -456,7 +456,7 @@ void xcvr2450::set_rx_gain(double gain, const std::string &name){
  * Bandwidth Handling
  **********************************************************************/
 static max2829_regs_t::tx_lpf_coarse_adj_t bandwidth_to_tx_lpf_coarse_reg(double &bandwidth){
-    int reg = std::clip(boost::math::iround((bandwidth-6.0e6)/6.0e6), 1, 3);
+    int reg = uhd::clip(boost::math::iround((bandwidth-6.0e6)/6.0e6), 1, 3);
 
     switch(reg){
     case 1: // bandwidth < 15MHz
@@ -473,7 +473,7 @@ static max2829_regs_t::tx_lpf_coarse_adj_t bandwidth_to_tx_lpf_coarse_reg(double
 }
 
 static max2829_regs_t::rx_lpf_fine_adj_t bandwidth_to_rx_lpf_fine_reg(double &bandwidth, double requested_bandwidth){
-    int reg = std::clip(boost::math::iround((requested_bandwidth/bandwidth)/0.05), 18, 22);
+    int reg = uhd::clip(boost::math::iround((requested_bandwidth/bandwidth)/0.05), 18, 22);
 
     switch(reg){
     case 18: // requested_bandwidth < 92.5%
@@ -496,7 +496,7 @@ static max2829_regs_t::rx_lpf_fine_adj_t bandwidth_to_rx_lpf_fine_reg(double &ba
 }
 
 static max2829_regs_t::rx_lpf_coarse_adj_t bandwidth_to_rx_lpf_coarse_reg(double &bandwidth){
-    int reg = std::clip(boost::math::iround((bandwidth-7.0e6)/1.0e6), 0, 11);
+    int reg = uhd::clip(boost::math::iround((bandwidth-7.0e6)/1.0e6), 0, 11);
 
     switch(reg){
     case 0: // bandwidth < 7.5MHz
diff --git a/host/lib/usrp/misc_utils.cpp b/host/lib/usrp/misc_utils.cpp
index 6fcbdfe3d..ddcad41cf 100644
--- a/host/lib/usrp/misc_utils.cpp
+++ b/host/lib/usrp/misc_utils.cpp
@@ -196,7 +196,7 @@ static void verify_xx_subdev_spec(
         wax::obj dboard = mboard[named_prop_t(dboard_prop, db_name)];
         BOOST_FOREACH(const std::string &sd_name, dboard[DBOARD_PROP_SUBDEV_NAMES].as<prop_names_t>()){
             try{
-                bool enable = std::has(subdev_spec, subdev_spec_pair_t(db_name, sd_name));
+                bool enable = uhd::has(subdev_spec, subdev_spec_pair_t(db_name, sd_name));
                 dboard[named_prop_t(DBOARD_PROP_SUBDEV, sd_name)][SUBDEV_PROP_ENABLED] = enable;
             }
             catch(const std::exception &e){
diff --git a/host/lib/usrp/usrp1/codec_ctrl.cpp b/host/lib/usrp/usrp1/codec_ctrl.cpp
index 56c3cee13..f9f923f38 100644
--- a/host/lib/usrp/usrp1/codec_ctrl.cpp
+++ b/host/lib/usrp/usrp1/codec_ctrl.cpp
@@ -162,7 +162,7 @@ static const int mtpgw = 255; //maximum tx pga gain word
 
 void usrp1_codec_ctrl_impl::set_tx_pga_gain(double gain){
     int gain_word = int(mtpgw*(gain - tx_pga_gain_range.start())/(tx_pga_gain_range.stop() - tx_pga_gain_range.start()));
-    _ad9862_regs.tx_pga_gain = std::clip(gain_word, 0, mtpgw);
+    _ad9862_regs.tx_pga_gain = uhd::clip(gain_word, 0, mtpgw);
     this->send_reg(16);
 }
 
@@ -174,7 +174,7 @@ static const int mrpgw = 0x14; //maximum rx pga gain word
 
 void usrp1_codec_ctrl_impl::set_rx_pga_gain(double gain, char which){
     int gain_word = int(mrpgw*(gain - rx_pga_gain_range.start())/(rx_pga_gain_range.stop() - rx_pga_gain_range.start()));
-    gain_word = std::clip(gain_word, 0, mrpgw);
+    gain_word = uhd::clip(gain_word, 0, mrpgw);
     switch(which){
     case 'A':
         _ad9862_regs.rx_pga_a = gain_word;
@@ -264,7 +264,7 @@ void usrp1_codec_ctrl_impl::write_aux_dac(aux_dac_t which, double volts)
 {
     //special case for aux dac d (aka sigma delta word)
     if (which == AUX_DAC_D) {
-        boost::uint16_t dac_word = std::clip(boost::math::iround(volts*0xfff/3.3), 0, 0xfff);
+        boost::uint16_t dac_word = uhd::clip(boost::math::iround(volts*0xfff/3.3), 0, 0xfff);
         _ad9862_regs.sig_delt_11_4 = boost::uint8_t(dac_word >> 4);
         _ad9862_regs.sig_delt_3_0 = boost::uint8_t(dac_word & 0xf);
         this->send_reg(42);
@@ -273,7 +273,7 @@ void usrp1_codec_ctrl_impl::write_aux_dac(aux_dac_t which, double volts)
     }
 
     //calculate the dac word for aux dac a, b, c
-    boost::uint8_t dac_word = std::clip(boost::math::iround(volts*0xff/3.3), 0, 0xff);
+    boost::uint8_t dac_word = uhd::clip(boost::math::iround(volts*0xff/3.3), 0, 0xff);
 
     //setup a lookup table for the aux dac params (reg ref, reg addr)
     typedef boost::tuple<boost::uint8_t*, boost::uint8_t> dac_params_t;
diff --git a/host/lib/usrp/usrp_e100/codec_ctrl.cpp b/host/lib/usrp/usrp_e100/codec_ctrl.cpp
index b5671072c..71a370f88 100644
--- a/host/lib/usrp/usrp_e100/codec_ctrl.cpp
+++ b/host/lib/usrp/usrp_e100/codec_ctrl.cpp
@@ -137,7 +137,7 @@ static const int mtpgw = 255; //maximum tx pga gain word
 
 void usrp_e100_codec_ctrl_impl::set_tx_pga_gain(double gain){
     int gain_word = int(mtpgw*(gain - tx_pga_gain_range.start())/(tx_pga_gain_range.stop() - tx_pga_gain_range.start()));
-    _ad9862_regs.tx_pga_gain = std::clip(gain_word, 0, mtpgw);
+    _ad9862_regs.tx_pga_gain = uhd::clip(gain_word, 0, mtpgw);
     this->send_reg(16);
 }
 
@@ -149,7 +149,7 @@ static const int mrpgw = 0x14; //maximum rx pga gain word
 
 void usrp_e100_codec_ctrl_impl::set_rx_pga_gain(double gain, char which){
     int gain_word = int(mrpgw*(gain - rx_pga_gain_range.start())/(rx_pga_gain_range.stop() - rx_pga_gain_range.start()));
-    gain_word = std::clip(gain_word, 0, mrpgw);
+    gain_word = uhd::clip(gain_word, 0, mrpgw);
     switch(which){
     case 'A':
         _ad9862_regs.rx_pga_a = gain_word;
@@ -236,7 +236,7 @@ double usrp_e100_codec_ctrl_impl::read_aux_adc(aux_adc_t which){
 void usrp_e100_codec_ctrl_impl::write_aux_dac(aux_dac_t which, double volts){
     //special case for aux dac d (aka sigma delta word)
     if (which == AUX_DAC_D){
-        boost::uint16_t dac_word = std::clip(boost::math::iround(volts*0xfff/3.3), 0, 0xfff);
+        boost::uint16_t dac_word = uhd::clip(boost::math::iround(volts*0xfff/3.3), 0, 0xfff);
         _ad9862_regs.sig_delt_11_4 = boost::uint8_t(dac_word >> 4);
         _ad9862_regs.sig_delt_3_0 = boost::uint8_t(dac_word & 0xf);
         this->send_reg(42);
@@ -245,7 +245,7 @@ void usrp_e100_codec_ctrl_impl::write_aux_dac(aux_dac_t which, double volts){
     }
 
     //calculate the dac word for aux dac a, b, c
-    boost::uint8_t dac_word = std::clip(boost::math::iround(volts*0xff/3.3), 0, 0xff);
+    boost::uint8_t dac_word = uhd::clip(boost::math::iround(volts*0xff/3.3), 0, 0xff);
 
     //setup a lookup table for the aux dac params (reg ref, reg addr)
     typedef boost::tuple<boost::uint8_t*, boost::uint8_t> dac_params_t;
diff --git a/host/lib/utils/gain_group.cpp b/host/lib/utils/gain_group.cpp
index 101620a33..3af8a543d 100644
--- a/host/lib/utils/gain_group.cpp
+++ b/host/lib/utils/gain_group.cpp
@@ -107,7 +107,7 @@ public:
         double gain_left_to_distribute = gain;
         BOOST_FOREACH(const gain_fcns_t &fcns, all_fcns){
             const gain_range_t range = fcns.get_range();
-            gain_bucket.push_back(floor_step(std::clip(
+            gain_bucket.push_back(floor_step(uhd::clip(
                 gain_left_to_distribute, range.start(), range.stop()
             ), max_step));
             gain_left_to_distribute -= gain_bucket.back();
@@ -131,7 +131,7 @@ public:
         //fill in the largest step sizes first that are less than the remainder
         BOOST_FOREACH(size_t i, indexes_step_size_dec){
             const gain_range_t range = all_fcns.at(i).get_range();
-            double additional_gain = floor_step(std::clip(
+            double additional_gain = floor_step(uhd::clip(
                 gain_bucket.at(i) + gain_left_to_distribute, range.start(), range.stop()
             ), range.step()) - gain_bucket.at(i);
             gain_bucket.at(i) += additional_gain;
@@ -167,7 +167,7 @@ private:
     //! get the gain function sets in order (highest priority first)
     std::vector<gain_fcns_t> get_all_fcns(void){
         std::vector<gain_fcns_t> all_fcns;
-        BOOST_FOREACH(size_t key, std::sorted(_registry.keys())){
+        BOOST_FOREACH(size_t key, uhd::sorted(_registry.keys())){
             const std::vector<gain_fcns_t> &fcns = _registry[key];
             all_fcns.insert(all_fcns.begin(), fcns.begin(), fcns.end());
         }
-- 
cgit v1.2.3