From 41e774c7c38ed8498e8bfad877f237ed090238ce Mon Sep 17 00:00:00 2001
From: Josh Blum <josh@joshknows.com>
Date: Thu, 13 Jan 2011 12:22:03 -0800
Subject: usrp1: implement soft time ctrl for send at, recv at

---
 host/lib/usrp/usrp1/soft_time_ctrl.cpp | 179 +++++++++++++++++++++++++++++++++
 1 file changed, 179 insertions(+)
 create mode 100644 host/lib/usrp/usrp1/soft_time_ctrl.cpp

(limited to 'host/lib/usrp/usrp1/soft_time_ctrl.cpp')

diff --git a/host/lib/usrp/usrp1/soft_time_ctrl.cpp b/host/lib/usrp/usrp1/soft_time_ctrl.cpp
new file mode 100644
index 000000000..8a6294690
--- /dev/null
+++ b/host/lib/usrp/usrp1/soft_time_ctrl.cpp
@@ -0,0 +1,179 @@
+//
+// Copyright 2011 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
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program.  If not, see <http://www.gnu.org/licenses/>.
+//
+
+#include "soft_time_ctrl.hpp"
+#include <uhd/transport/bounded_buffer.hpp>
+#include <boost/any.hpp>
+#include <boost/thread.hpp>
+#include <boost/date_time/posix_time/posix_time.hpp>
+#include <boost/date_time/local_time/local_time.hpp>
+#include <iostream>
+
+using namespace uhd;
+using namespace uhd::usrp;
+using namespace uhd::transport;
+namespace pt = boost::posix_time;
+namespace lt = boost::local_time;
+
+/***********************************************************************
+ * Utility helper functions
+ **********************************************************************/
+
+//TODO put these in time_spec_t (maybe useful)
+
+time_spec_t time_dur_to_time_spec(const pt::time_duration &time_dur){
+    return time_spec_t(
+        time_dur.total_seconds(),
+        time_dur.fractional_seconds(),
+        pt::time_duration::ticks_per_second()
+    );
+}
+
+pt::time_duration time_spec_to_time_dur(const time_spec_t &time_spec){
+    return pt::time_duration(
+        0, 0, time_spec.get_full_secs(),
+        time_spec.get_tick_count(pt::time_duration::ticks_per_second())
+    );
+}
+
+/***********************************************************************
+ * Soft time control implementation
+ **********************************************************************/
+class soft_time_ctrl_impl : public soft_time_ctrl{
+public:
+    soft_time_ctrl_impl(const cb_fcn_type &stream_on_off):
+        _nsamps_remaining(0),
+        _stream_mode(stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS),
+        _cmd_queue(bounded_buffer<boost::any>::make(2)),
+        _stream_on_off(stream_on_off)
+    {
+        //synchronously spawn a new thread
+        _update_mutex.lock(); //lock mutex before spawned
+        _thread_group.create_thread(boost::bind(&soft_time_ctrl_impl::recv_cmd_dispatcher, this));
+        _update_mutex.lock(); //lock blocks until spawned
+        _update_mutex.unlock(); //unlock mutex before done
+    }
+
+    ~soft_time_ctrl_impl(void){
+        _thread_running = false;
+        _thread_group.join_all();
+    }
+
+    void set_time(const time_spec_t &time){
+        _time_offset = pt::microsec_clock::universal_time() - time_spec_to_time_dur(time);
+    }
+
+    time_spec_t get_time(void){
+        return time_dur_to_time_spec(pt::microsec_clock::universal_time() - _time_offset);
+    }
+
+    void recv_post(rx_metadata_t &md, size_t &nsamps){
+        //load the metadata with the current time
+        md.has_time_spec = true;
+        md.time_spec = get_time();
+
+        //lock the mutex here before changing state
+        boost::mutex::scoped_lock lock(_update_mutex);
+
+        //When to stop streaming:
+        //The samples have been received and the stream mode is non-continuous.
+        //Rewrite the sample count to clip to the requested number of samples.
+        if (_nsamps_remaining <= nsamps and
+            _stream_mode != stream_cmd_t::STREAM_MODE_START_CONTINUOUS
+        ){
+            nsamps = _nsamps_remaining; //set nsamps, then stop
+            stream_on_off(false);
+            return;
+        }
+
+        //update the consumed samples
+        _nsamps_remaining -= nsamps;
+    }
+
+    void send_pre(const tx_metadata_t &md, double /*TODO timeout*/){
+        if (not md.has_time_spec) return;
+        sleep_until_time(md.time_spec); //TODO late?
+    }
+
+    void issue_stream_cmd(const stream_cmd_t &cmd){
+        _cmd_queue->push_with_wait(cmd);
+    }
+
+private:
+
+    void sleep_until_time(const time_spec_t &time){
+        boost::this_thread::sleep(_time_offset + time_spec_to_time_dur(time));
+    }
+
+    void recv_cmd_handle_cmd(const stream_cmd_t &cmd){
+        //handle the stream at time by sleeping
+        if (not cmd.stream_now) sleep_until_time(cmd.time_spec); //TODO late?
+
+        //lock the mutex here before changing state
+        boost::mutex::scoped_lock lock(_update_mutex);
+
+        //When to stop streaming:
+        //Stop streaming when the command is a stop and streaming.
+        if (cmd.stream_mode == stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS
+           and _stream_mode != stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS
+        ) stream_on_off(false);
+
+        //When to start streaming:
+        //Start streaming when the command is not a stop and not streaming.
+        if (cmd.stream_mode != stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS
+           and _stream_mode == stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS
+        ) stream_on_off(true);
+
+        //update the state
+        _nsamps_remaining += cmd.num_samps;
+        _stream_mode = cmd.stream_mode;
+    }
+
+    void recv_cmd_dispatcher(void){
+        _thread_running = true;
+        _update_mutex.unlock();
+
+        boost::any cmd;
+        while (_thread_running){
+            if (_cmd_queue->pop_with_timed_wait(cmd, 1.0)){
+                recv_cmd_handle_cmd(boost::any_cast<stream_cmd_t>(cmd));
+            }
+        }
+    }
+
+    void stream_on_off(bool stream){
+        _stream_on_off(stream);
+        _nsamps_remaining = 0;
+    }
+
+    boost::mutex _update_mutex;
+    size_t _nsamps_remaining;
+    stream_cmd_t::stream_mode_t _stream_mode;
+
+    pt::ptime _time_offset;
+    bounded_buffer<boost::any>::sptr _cmd_queue;
+    const cb_fcn_type _stream_on_off;
+    boost::thread_group _thread_group;
+    bool _thread_running;
+};
+
+/***********************************************************************
+ * Soft time control factor
+ **********************************************************************/
+soft_time_ctrl::sptr soft_time_ctrl::make(const cb_fcn_type &stream_on_off){
+    return sptr(new soft_time_ctrl_impl(stream_on_off));
+}
-- 
cgit v1.2.3


From d71344091b324266975b58ec075d896fcb79aeb9 Mon Sep 17 00:00:00 2001
From: Josh Blum <josh@joshknows.com>
Date: Mon, 17 Jan 2011 15:18:46 -0800
Subject: usrp1: work on usrp1 hardware compat with the api

today we added shutoff the DAC when not transmitting using EOB as an indicator

added various other features and cleaned up code for soft time control
---
 host/docs/usrp1.rst                    |   3 +-
 host/lib/usrp/usrp1/codec_ctrl.cpp     |   6 ++
 host/lib/usrp/usrp1/codec_ctrl.hpp     |   5 +-
 host/lib/usrp/usrp1/io_impl.cpp        |  36 ++++++++--
 host/lib/usrp/usrp1/mboard_impl.cpp    |   8 ---
 host/lib/usrp/usrp1/soft_time_ctrl.cpp | 122 ++++++++++++++++++++++-----------
 host/lib/usrp/usrp1/soft_time_ctrl.hpp |   5 +-
 host/lib/usrp/usrp1/usrp1_ctrl.cpp     |  29 +++++---
 host/lib/usrp/usrp1/usrp1_ctrl.hpp     |  17 +----
 host/lib/usrp/usrp1/usrp1_impl.cpp     |   8 +--
 host/lib/usrp/usrp1/usrp1_impl.hpp     |   3 +-
 11 files changed, 156 insertions(+), 86 deletions(-)

(limited to 'host/lib/usrp/usrp1/soft_time_ctrl.cpp')

diff --git a/host/docs/usrp1.rst b/host/docs/usrp1.rst
index 44ddb20ca..a8d3193fd 100644
--- a/host/docs/usrp1.rst
+++ b/host/docs/usrp1.rst
@@ -80,6 +80,7 @@ List of emulated features
 * Transmitting at a specific time
 * Receiving at a specific time
 * Receiving a specific number of samples
+* Start and end burst flags on transmit
 
 **Note:**
 These emulated features rely on the host system's clock for timed operations,
@@ -92,7 +93,7 @@ List of missing features
 * Notification on late transmit packet
 * Notification on broken chain error
 * Notification on underflow or overflow
-* Transmit and receive burst flags
+* Start and end burst flags for receive
 
 ------------------------------------------------------------------------
 OS specific notes
diff --git a/host/lib/usrp/usrp1/codec_ctrl.cpp b/host/lib/usrp/usrp1/codec_ctrl.cpp
index 6342bb057..f3816b377 100644
--- a/host/lib/usrp/usrp1/codec_ctrl.cpp
+++ b/host/lib/usrp/usrp1/codec_ctrl.cpp
@@ -55,6 +55,7 @@ public:
 
     //duc control
     void set_duc_freq(double freq);
+    void enable_tx_digital(bool enb);
 
     //pga gain control
     void set_tx_pga_gain(double);
@@ -421,6 +422,11 @@ void usrp1_codec_ctrl_impl::set_duc_freq(double freq)
     this->send_reg(23);
 }
 
+void usrp1_codec_ctrl_impl::enable_tx_digital(bool enb){
+    _ad9862_regs.tx_digital_pd = (enb)? 0 : 1;
+    this->send_reg(8);
+}
+
 /***********************************************************************
  * Codec Control ADC buffer bypass
  * Disable this for AC-coupled daughterboards (TVRX)
diff --git a/host/lib/usrp/usrp1/codec_ctrl.hpp b/host/lib/usrp/usrp1/codec_ctrl.hpp
index 043acc8bd..20e4015c5 100644
--- a/host/lib/usrp/usrp1/codec_ctrl.hpp
+++ b/host/lib/usrp/usrp1/codec_ctrl.hpp
@@ -92,7 +92,10 @@ public:
 
     //! Set the TX modulator frequency
     virtual void set_duc_freq(double freq) = 0;
-    
+
+    //! Enable or disable the digital part of the DAC
+    virtual void enable_tx_digital(bool enb) = 0;
+
     //! Enable or disable ADC buffer bypass
     virtual void bypass_adc_buffers(bool bypass) = 0;
 };
diff --git a/host/lib/usrp/usrp1/io_impl.cpp b/host/lib/usrp/usrp1/io_impl.cpp
index b5d4970c4..9fa1b4f72 100644
--- a/host/lib/usrp/usrp1/io_impl.cpp
+++ b/host/lib/usrp/usrp1/io_impl.cpp
@@ -91,6 +91,7 @@ struct usrp1_impl::io_impl{
     void commit_send_buff(offset_send_buffer::sptr, offset_send_buffer::sptr, size_t);
     void flush_send_buff(void);
     bool get_send_buffs(vrt_packet_handler::managed_send_buffs_t &, double);
+    bool transmitting_enb;
 };
 
 /*!
@@ -183,6 +184,28 @@ void usrp1_impl::io_init(void){
     _tx_otw_type.byteorder = otw_type_t::BO_LITTLE_ENDIAN;
 
     _io_impl = UHD_PIMPL_MAKE(io_impl, (_data_transport));
+
+    _soft_time_ctrl = soft_time_ctrl::make(
+        boost::bind(&usrp1_impl::rx_stream_on_off, this, _1)
+    );
+
+    rx_stream_on_off(false);
+    tx_stream_on_off(false);
+}
+
+void usrp1_impl::rx_stream_on_off(bool enb){
+    return _iface->write_firmware_cmd(VRQ_FPGA_SET_RX_ENABLE, enb, 0, 0, 0);
+    //drain any junk in the receive transport after stop streaming command
+    while(not enb and _data_transport->get_recv_buff().get() != NULL){
+        /* NOP */
+    }
+}
+
+void usrp1_impl::tx_stream_on_off(bool enb){
+    if (not enb) _io_impl->flush_send_buff();
+    _codec_ctrls[DBOARD_SLOT_A]->enable_tx_digital(enb);
+    _codec_ctrls[DBOARD_SLOT_B]->enable_tx_digital(enb);
+    _io_impl->transmitting_enb = enb;
 }
 
 /***********************************************************************
@@ -208,7 +231,9 @@ size_t usrp1_impl::send(
     const tx_metadata_t &metadata, const io_type_t &io_type,
     send_mode_t send_mode, double timeout
 ){
-    _soft_time_ctrl->send_pre(metadata, timeout);
+    if (_soft_time_ctrl->send_pre(metadata, timeout)) return num_samps;
+    if (not _io_impl->transmitting_enb) tx_stream_on_off(true);
+
     size_t num_samps_sent = vrt_packet_handler::send(
         _io_impl->packet_handler_send_state,       //last state of the send handler
         buffs, num_samps,                          //buffer to fill
@@ -222,9 +247,11 @@ size_t usrp1_impl::send(
         _tx_subdev_spec.size()                     //num channels
     );
 
-    //Don't honor sob because it is normal to be always bursting...
-    //handle eob flag (commit the buffer)
-    if (metadata.end_of_burst) _io_impl->flush_send_buff();
+    //handle eob flag (commit the buffer, disable the DACs)
+    //check num samps sent to avoid flush on incomplete/timeout
+    if (metadata.end_of_burst and num_samps_sent == num_samps){
+        this->tx_stream_on_off(false);
+    }
 
     //handle the polling for underflow conditions
     _io_impl->underflow_poll_samp_count += num_samps_sent;
@@ -295,6 +322,7 @@ size_t usrp1_impl::recv(
         0,                                         //vrt header offset
         _rx_subdev_spec.size()                     //num channels
     );
+
     _soft_time_ctrl->recv_post(metadata, num_samps_recvd);
 
     //handle the polling for overflow conditions
diff --git a/host/lib/usrp/usrp1/mboard_impl.cpp b/host/lib/usrp/usrp1/mboard_impl.cpp
index 2804671b7..23c8f03c4 100644
--- a/host/lib/usrp/usrp1/mboard_impl.cpp
+++ b/host/lib/usrp/usrp1/mboard_impl.cpp
@@ -240,14 +240,6 @@ void usrp1_impl::mboard_init(void)
     }
 }
 
-void usrp1_impl::stream_on_off(bool stream){
-    return _iface->write_firmware_cmd(VRQ_FPGA_SET_RX_ENABLE, stream, 0, 0, 0);
-    //drain any junk in the receive transport after stop streaming command
-    while(not stream and _data_transport->get_recv_buff(0.0).get() != NULL){
-        /* NOP */
-    }
-}
-
 /***********************************************************************
  * Mboard Get
  **********************************************************************/
diff --git a/host/lib/usrp/usrp1/soft_time_ctrl.cpp b/host/lib/usrp/usrp1/soft_time_ctrl.cpp
index 8a6294690..512327150 100644
--- a/host/lib/usrp/usrp1/soft_time_ctrl.cpp
+++ b/host/lib/usrp/usrp1/soft_time_ctrl.cpp
@@ -29,24 +29,28 @@ using namespace uhd::transport;
 namespace pt = boost::posix_time;
 namespace lt = boost::local_time;
 
+static const time_spec_t TWIDDLE(0.0015);
+
 /***********************************************************************
  * Utility helper functions
  **********************************************************************/
 
 //TODO put these in time_spec_t (maybe useful)
 
+static const double time_dur_tps = double(pt::time_duration::ticks_per_second());
+
 time_spec_t time_dur_to_time_spec(const pt::time_duration &time_dur){
     return time_spec_t(
         time_dur.total_seconds(),
-        time_dur.fractional_seconds(),
-        pt::time_duration::ticks_per_second()
+        long(time_dur.fractional_seconds()),
+        time_dur_tps
     );
 }
 
 pt::time_duration time_spec_to_time_dur(const time_spec_t &time_spec){
     return pt::time_duration(
-        0, 0, time_spec.get_full_secs(),
-        time_spec.get_tick_count(pt::time_duration::ticks_per_second())
+        0, 0, long(time_spec.get_full_secs()),
+        time_spec.get_tick_count(time_dur_tps)
     );
 }
 
@@ -55,6 +59,7 @@ pt::time_duration time_spec_to_time_dur(const time_spec_t &time_spec){
  **********************************************************************/
 class soft_time_ctrl_impl : public soft_time_ctrl{
 public:
+
     soft_time_ctrl_impl(const cb_fcn_type &stream_on_off):
         _nsamps_remaining(0),
         _stream_mode(stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS),
@@ -69,32 +74,53 @@ public:
     }
 
     ~soft_time_ctrl_impl(void){
-        _thread_running = false;
+        _thread_group.interrupt_all();
         _thread_group.join_all();
     }
 
+    /*******************************************************************
+     * Time control
+     ******************************************************************/
     void set_time(const time_spec_t &time){
-        _time_offset = pt::microsec_clock::universal_time() - time_spec_to_time_dur(time);
+        boost::mutex::scoped_lock lock(_update_mutex);
+        _time_offset = boost::get_system_time() - time_spec_to_time_dur(time);
     }
 
     time_spec_t get_time(void){
-        return time_dur_to_time_spec(pt::microsec_clock::universal_time() - _time_offset);
+        boost::mutex::scoped_lock lock(_update_mutex);
+        return time_now();
     }
 
+    UHD_INLINE time_spec_t time_now(void){
+        //internal get time without scoped lock
+        return time_dur_to_time_spec(boost::get_system_time() - _time_offset);
+    }
+
+    UHD_INLINE void sleep_until_time(
+        boost::mutex::scoped_lock &lock, const time_spec_t &time
+    ){
+        boost::condition_variable cond;
+        //use a condition variable to unlock, sleep, lock
+        cond.timed_wait(lock, _time_offset + time_spec_to_time_dur(time));
+    }
+
+    /*******************************************************************
+     * Receive control
+     ******************************************************************/
     void recv_post(rx_metadata_t &md, size_t &nsamps){
-        //load the metadata with the current time
+        boost::mutex::scoped_lock lock(_update_mutex);
+
+        //load the metadata with the expected time
         md.has_time_spec = true;
-        md.time_spec = get_time();
+        md.time_spec = time_now();
 
-        //lock the mutex here before changing state
-        boost::mutex::scoped_lock lock(_update_mutex);
+        //none of the stuff below matters in continuous streaming mode
+        if (_stream_mode == stream_cmd_t::STREAM_MODE_START_CONTINUOUS) return;
 
         //When to stop streaming:
         //The samples have been received and the stream mode is non-continuous.
         //Rewrite the sample count to clip to the requested number of samples.
-        if (_nsamps_remaining <= nsamps and
-            _stream_mode != stream_cmd_t::STREAM_MODE_START_CONTINUOUS
-        ){
+        if (_nsamps_remaining <= nsamps){
             nsamps = _nsamps_remaining; //set nsamps, then stop
             stream_on_off(false);
             return;
@@ -104,28 +130,53 @@ public:
         _nsamps_remaining -= nsamps;
     }
 
-    void send_pre(const tx_metadata_t &md, double /*TODO timeout*/){
-        if (not md.has_time_spec) return;
-        sleep_until_time(md.time_spec); //TODO late?
-    }
-
     void issue_stream_cmd(const stream_cmd_t &cmd){
         _cmd_queue->push_with_wait(cmd);
     }
 
-private:
+    void stream_on_off(bool enb){
+        _stream_on_off(enb);
+        _nsamps_remaining = 0;
+    }
 
-    void sleep_until_time(const time_spec_t &time){
-        boost::this_thread::sleep(_time_offset + time_spec_to_time_dur(time));
+    /*******************************************************************
+     * Transmit control
+     ******************************************************************/
+    bool send_pre(const tx_metadata_t &md, double &timeout){
+        if (not md.has_time_spec) return false;
+
+        boost::mutex::scoped_lock lock(_update_mutex);
+
+        time_spec_t time_at(md.time_spec - TWIDDLE);
+
+        //handle late packets
+        if (time_at < time_now()){
+            //TODO post async message
+            return true;
+        }
+
+        timeout -= (time_at - time_now()).get_real_secs();
+        sleep_until_time(lock, time_at);
+        return false;
     }
 
+    /*******************************************************************
+     * Thread control
+     ******************************************************************/
     void recv_cmd_handle_cmd(const stream_cmd_t &cmd){
-        //handle the stream at time by sleeping
-        if (not cmd.stream_now) sleep_until_time(cmd.time_spec); //TODO late?
-
-        //lock the mutex here before changing state
         boost::mutex::scoped_lock lock(_update_mutex);
 
+        //handle the stream at time by sleeping
+        if (not cmd.stream_now){
+            time_spec_t time_at(cmd.time_spec - TWIDDLE);
+            if (time_at < time_now()){
+                //TODO inject late cmd inline error
+            }
+            else{
+                sleep_until_time(lock, time_at);
+            }
+        }
+
         //When to stop streaming:
         //Stop streaming when the command is a stop and streaming.
         if (cmd.stream_mode == stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS
@@ -144,31 +195,24 @@ private:
     }
 
     void recv_cmd_dispatcher(void){
-        _thread_running = true;
         _update_mutex.unlock();
-
-        boost::any cmd;
-        while (_thread_running){
-            if (_cmd_queue->pop_with_timed_wait(cmd, 1.0)){
+        try{
+            boost::any cmd;
+            while (true){
+                _cmd_queue->pop_with_wait(cmd);
                 recv_cmd_handle_cmd(boost::any_cast<stream_cmd_t>(cmd));
             }
-        }
-    }
-
-    void stream_on_off(bool stream){
-        _stream_on_off(stream);
-        _nsamps_remaining = 0;
+        } catch(const boost::thread_interrupted &){}
     }
 
+private:
     boost::mutex _update_mutex;
     size_t _nsamps_remaining;
     stream_cmd_t::stream_mode_t _stream_mode;
-
     pt::ptime _time_offset;
     bounded_buffer<boost::any>::sptr _cmd_queue;
     const cb_fcn_type _stream_on_off;
     boost::thread_group _thread_group;
-    bool _thread_running;
 };
 
 /***********************************************************************
diff --git a/host/lib/usrp/usrp1/soft_time_ctrl.hpp b/host/lib/usrp/usrp1/soft_time_ctrl.hpp
index 42056c285..7fdac7fc8 100644
--- a/host/lib/usrp/usrp1/soft_time_ctrl.hpp
+++ b/host/lib/usrp/usrp1/soft_time_ctrl.hpp
@@ -41,8 +41,7 @@ public:
 
     /*!
      * Make a new soft time control.
-     * \param start_streaming a function callback to start streaming
-     * \param stop_streaming a function callback to stop streaming
+     * \param stream_on_off a function to enable/disable rx
      * \return a new soft time control object
      */
     static sptr make(const cb_fcn_type &stream_on_off);
@@ -59,7 +58,7 @@ public:
     virtual void recv_post(rx_metadata_t &md, size_t &nsamps) = 0;
 
     //! Call before the internal send function
-    virtual void send_pre(const tx_metadata_t &md, double timeout) = 0;
+    virtual bool send_pre(const tx_metadata_t &md, double &timeout) = 0;
 
     //! Issue a stream command to receive
     virtual void issue_stream_cmd(const stream_cmd_t &cmd) = 0;
diff --git a/host/lib/usrp/usrp1/usrp1_ctrl.cpp b/host/lib/usrp/usrp1/usrp1_ctrl.cpp
index 5043aed7d..09f854813 100644
--- a/host/lib/usrp/usrp1/usrp1_ctrl.cpp
+++ b/host/lib/usrp/usrp1/usrp1_ctrl.cpp
@@ -139,13 +139,6 @@ public:
         _ctrl_transport = ctrl_transport;
     }
 
-
-    ~usrp_ctrl_impl(void)
-    {
-        /* NOP */
-    }
-
-
     int usrp_load_firmware(std::string filestring, bool force)
     {
         const char *filename = filestring.c_str();
@@ -233,6 +226,20 @@ public:
         return -1;
     }
 
+    void usrp_init(void){
+        /* not calling because this causes junk to come at init
+         * and it does not seem to be necessary to call anyway
+        usrp_rx_enable(false);
+        usrp_rx_reset(true);
+        usrp_rx_reset(false);
+        usrp_rx_enable(true);
+        */
+
+        usrp_tx_enable(false);
+        usrp_tx_reset(true);
+        usrp_tx_reset(false);
+        usrp_tx_enable(true);
+    }
 
     int usrp_load_fpga(std::string filestring)
     {
@@ -288,7 +295,7 @@ public:
         usrp_set_fpga_hash(hash);
         file.close();
         if (load_img_msg) std::cout << " done" << std::endl;
-        return 0; 
+        return 0;
     }
 
     int usrp_load_eeprom(std::string filestring)
@@ -393,6 +400,12 @@ public:
     }
 
 
+    int usrp_rx_reset(bool on)
+    {
+        return usrp_control_write_cmd(VRQ_FPGA_SET_RX_RESET, on, 0); 
+    }
+
+
     int usrp_control_write(boost::uint8_t request,
                            boost::uint16_t value,
                            boost::uint16_t index,
diff --git a/host/lib/usrp/usrp1/usrp1_ctrl.hpp b/host/lib/usrp/usrp1/usrp1_ctrl.hpp
index a02d9f96c..8ccfacab7 100644
--- a/host/lib/usrp/usrp1/usrp1_ctrl.hpp
+++ b/host/lib/usrp/usrp1/usrp1_ctrl.hpp
@@ -33,6 +33,9 @@ public:
      */
     static sptr make(uhd::transport::usb_control::sptr ctrl_transport);
 
+    //! Call init after the fpga is loaded
+    virtual void usrp_init(void) = 0;
+
     /*!
      * Load firmware in Intel HEX Format onto device 
      * \param filename name of firmware file
@@ -92,20 +95,6 @@ public:
      */
     virtual int usrp_set_fpga_hash(size_t hash) = 0;
 
-    /*!
-     * Set rx enable or disable 
-     * \param on enable or disable value
-     * \return 0 on success, error code otherwise
-     */
-    virtual int usrp_rx_enable(bool on) = 0;
-
-    /*!
-     * Set rx enable or disable 
-     * \param on enable or disable value
-     * \return 0 on success, error code otherwise
-     */
-    virtual int usrp_tx_enable(bool on) = 0;
-
     /*!
      * Submit an IN transfer 
      * \param request device specific request 
diff --git a/host/lib/usrp/usrp1/usrp1_impl.cpp b/host/lib/usrp/usrp1/usrp1_impl.cpp
index 04a199928..c395db0b9 100644
--- a/host/lib/usrp/usrp1/usrp1_impl.cpp
+++ b/host/lib/usrp/usrp1/usrp1_impl.cpp
@@ -139,6 +139,7 @@ static device::sptr usrp1_make(const device_addr_t &device_addr){
     usb_control::sptr ctrl_transport = usb_control::make(handle);
     usrp_ctrl::sptr usrp_ctrl = usrp_ctrl::make(ctrl_transport);
     usrp_ctrl->usrp_load_fpga(usrp1_fpga_image);
+    usrp_ctrl->usrp_init();
     usb_zero_copy::sptr data_transport = usb_zero_copy::make(
         handle,        // identifier
         6,             // IN endpoint
@@ -161,10 +162,6 @@ usrp1_impl::usrp1_impl(uhd::transport::usb_zero_copy::sptr data_transport,
                        usrp_ctrl::sptr ctrl_transport)
  : _data_transport(data_transport), _ctrl_transport(ctrl_transport)
 {
-    _soft_time_ctrl = soft_time_ctrl::make(
-        boost::bind(&usrp1_impl::stream_on_off, this, _1)
-    );
-
     _iface = usrp1_iface::make(ctrl_transport);
 
     //create clock interface
@@ -196,9 +193,6 @@ usrp1_impl::usrp1_impl(uhd::transport::usb_zero_copy::sptr data_transport,
     //initialize the send/recv
     io_init();
 
-    //turn on the transmitter
-    _ctrl_transport->usrp_tx_enable(true);
-
     //init the subdev specs
     this->mboard_set(MBOARD_PROP_RX_SUBDEV_SPEC, subdev_spec_t());
     this->mboard_set(MBOARD_PROP_TX_SUBDEV_SPEC, subdev_spec_t());
diff --git a/host/lib/usrp/usrp1/usrp1_impl.hpp b/host/lib/usrp/usrp1/usrp1_impl.hpp
index 18a8683a7..057725394 100644
--- a/host/lib/usrp/usrp1/usrp1_impl.hpp
+++ b/host/lib/usrp/usrp1/usrp1_impl.hpp
@@ -124,7 +124,8 @@ private:
     //handle io stuff
     UHD_PIMPL_DECL(io_impl) _io_impl;
     void io_init(void);
-    void stream_on_off(bool);
+    void rx_stream_on_off(bool);
+    void tx_stream_on_off(bool);
     void handle_overrun(size_t);
 
     //underrun and overrun poll intervals
-- 
cgit v1.2.3


From 8e0fbbe47b3c0b2805d2a638da7f363bee2240fd Mon Sep 17 00:00:00 2001
From: Josh Blum <josh@joshknows.com>
Date: Tue, 18 Jan 2011 14:59:36 -0800
Subject: usrp1: set eob on md when shutting off receiver, because we can

---
 host/docs/usrp1.rst                    | 4 ++--
 host/lib/usrp/usrp1/soft_time_ctrl.cpp | 1 +
 2 files changed, 3 insertions(+), 2 deletions(-)

(limited to 'host/lib/usrp/usrp1/soft_time_ctrl.cpp')

diff --git a/host/docs/usrp1.rst b/host/docs/usrp1.rst
index a8d3193fd..0a8224850 100644
--- a/host/docs/usrp1.rst
+++ b/host/docs/usrp1.rst
@@ -80,7 +80,7 @@ List of emulated features
 * Transmitting at a specific time
 * Receiving at a specific time
 * Receiving a specific number of samples
-* Start and end burst flags on transmit
+* End of burst flags for transmit/receive
 
 **Note:**
 These emulated features rely on the host system's clock for timed operations,
@@ -93,7 +93,7 @@ List of missing features
 * Notification on late transmit packet
 * Notification on broken chain error
 * Notification on underflow or overflow
-* Start and end burst flags for receive
+* Start of burst flags for transmit/receive
 
 ------------------------------------------------------------------------
 OS specific notes
diff --git a/host/lib/usrp/usrp1/soft_time_ctrl.cpp b/host/lib/usrp/usrp1/soft_time_ctrl.cpp
index 512327150..4d6abe218 100644
--- a/host/lib/usrp/usrp1/soft_time_ctrl.cpp
+++ b/host/lib/usrp/usrp1/soft_time_ctrl.cpp
@@ -122,6 +122,7 @@ public:
         //Rewrite the sample count to clip to the requested number of samples.
         if (_nsamps_remaining <= nsamps){
             nsamps = _nsamps_remaining; //set nsamps, then stop
+            md.end_of_burst = true;
             stream_on_off(false);
             return;
         }
-- 
cgit v1.2.3