usrp2.h

Go to the documentation of this file.
00001 /* -*- c++ -*- */
00002 /*
00003  * Copyright 2008,2009 Free Software Foundation, Inc.
00004  *
00005  * This program is free software: you can redistribute it and/or modify
00006  * it under the terms of the GNU General Public License as published by
00007  * the Free Software Foundation, either version 3 of the License, or
00008  * (at your option) any later version.
00009  *
00010  * This program is distributed in the hope that it will be useful,
00011  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00012  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00013  * GNU General Public License for more details.
00014  *
00015  * You should have received a copy of the GNU General Public License
00016  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
00017  */
00018 
00019 #ifndef INCLUDED_USRP2_H
00020 #define INCLUDED_USRP2_H
00021 
00022 #include <boost/shared_ptr.hpp>
00023 #include <boost/utility.hpp>
00024 #include <vector>
00025 #include <complex>
00026 #include <usrp2/rx_sample_handler.h>
00027 #include <usrp2/tune_result.h>
00028 #include <usrp2/mimo_config.h>
00029 
00030 /*
00031  * N.B., The interfaces described here are still in flux.
00032  *
00033  * We will keep all the code in the tree up-to-date with regard to changes
00034  * here, but reserve the right to change this on a whim.
00035  */
00036 
00037 namespace usrp2 {
00038 
00039   /*!
00040    * Structure to hold properties of USRP2 hardware devices.
00041    *
00042    */
00043   struct props
00044   {
00045     std::string addr;
00046     uint16_t hw_rev;
00047     uint8_t fpga_md5sum[16];
00048     uint8_t sw_md5sum[16];
00049   };
00050 
00051   typedef std::vector<props> props_vector_t;
00052 
00053   /*!
00054    * \brief Search the ethernet for all USRP2s or for a specific USRP2.
00055    *
00056    * \param ifc is the name of the OS ethernet interface (e.g., "eth0")
00057    * \param mac_addr is the MAC address of the desired USRP2, or "" to search for all.
00058    * mac_addr must be either a zero length string, "", or must be of the form
00059    * "01:02:03:04:05:06" or "05:06".
00060    *
00061    * \returns a vector of properties, 1 entry for each matching USRP2 found.
00062    */
00063   props_vector_t find(const std::string &ifc, const std::string &mac_addr=""); 
00064 
00065   class tune_result;
00066 
00067   // FIXME: get from firmware include
00068   static const int GPIO_TX_BANK = 0;
00069   static const int GPIO_RX_BANK = 1;
00070 
00071   /*!
00072    * \brief standard C++ interface to USRP2
00073    * \ingroup usrp2
00074    */
00075   class usrp2 : boost::noncopyable
00076   {
00077   public:
00078     static const unsigned int MAX_CHAN = 30;
00079 
00080     /*!
00081      * Shared pointer to this class
00082      */ 
00083     typedef boost::shared_ptr<usrp2> sptr;
00084  
00085     /*! 
00086      * Static function to return an instance of usrp2 as a shared pointer
00087      *
00088      * \param ifc   Network interface name, e.g., "eth0"
00089      * \param addr  Network mac address, e.g., "01:23:45:67:89:ab", "89:ab" or "".
00090      *              If \p addr is HH:HH, it's treated as if it were 00:50:c2:85:HH:HH
00091      *              "" will autoselect a USRP2 if there is only a single one on the local ethernet.
00092      * \param rx_bufsize is the length in bytes of the kernel networking buffer to allocate.
00093      */
00094     static sptr make(const std::string &ifc, const std::string &addr="", size_t rx_bufsize=0);
00095 
00096     /*!
00097      * Class destructor
00098      */
00099     ~usrp2();  
00100 
00101     /*!
00102      * Returns the MAC address associated with this USRP
00103      */
00104     std::string mac_addr();
00105 
00106     /*!
00107      * Returns the GbE interface name associated with this USRP
00108      */
00109     std::string interface_name();
00110 
00111     /*
00112      * ----------------------------------------------------------------
00113      * Rx configuration and control
00114      * ----------------------------------------------------------------
00115      */
00116 
00117     /*!
00118      * Set receiver gain
00119      * \param gain in dB (more or less)
00120      */
00121     bool set_rx_gain(double gain);
00122 
00123     //! return minimum Rx gain 
00124     double rx_gain_min();
00125 
00126     //! return maximum Rx gain 
00127     double rx_gain_max();
00128 
00129     //! return Rx gain db_per_step
00130     double rx_gain_db_per_step();
00131 
00132     /*!
00133      * \brief Set receive daughterboard LO offset frequency
00134      */
00135     bool set_rx_lo_offset(double frequency);
00136 
00137     /*!
00138      * Set receiver center frequency
00139      */
00140     bool set_rx_center_freq(double frequency, tune_result *result);
00141 
00142     //! return minimum Rx center frequency
00143     double rx_freq_min();
00144 
00145     //! return maximum Rx center frequency
00146     double rx_freq_max();
00147 
00148     /*!
00149      * Set receiver sample rate decimation
00150      */
00151     bool set_rx_decim(int decimation_factor);
00152 
00153     //! Return current decimation factor
00154     int rx_decim();
00155 
00156     /*!
00157      * Set receiver IQ magnitude scaling
00158      */
00159     bool set_rx_scale_iq(int scale_i, int scale_q);
00160 
00161     /*!
00162      * Set received sample format
00163      *   
00164      *    domain: complex or real
00165      *      type: floating, fixed point, or raw
00166      *     depth: bits per sample
00167      *
00168      * Sets format over the wire for samples from USRP2.
00169      */
00170     // bool set_rx_format(...);
00171 
00172     /*!
00173      * Start streaming receive mode.  USRP2 will send a continuous stream of
00174      * DSP pipeline samples to host.  Call rx_samples(...) to access.
00175      * 
00176      * \param channel          Stream channel number (0-30)
00177      * \param items_per_frame  Number of 32-bit items per frame.
00178      */
00179     bool start_rx_streaming(unsigned int channel=0, unsigned int items_per_frame=0);
00180   
00181     /*!
00182      * Stop streaming receive mode.
00183      */
00184     bool stop_rx_streaming(unsigned int channel=0);
00185 
00186     /*!
00187      * \brief Receive data from the specified channel
00188      * This method is used to receive all data: streaming or discrete.
00189      */
00190     bool rx_samples(unsigned int channel, rx_sample_handler *handler);
00191 
00192     /*!
00193      * Returns number of times receive overruns have occurred
00194      */
00195     unsigned int rx_overruns();
00196     
00197     /*!
00198      * Returns total number of missing frames from overruns.
00199      */
00200     unsigned int rx_missing();
00201 
00202     /*
00203      * ----------------------------------------------------------------
00204      * Tx configuration and control
00205      * ----------------------------------------------------------------
00206      */
00207 
00208     /*!
00209      * Set transmitter gain
00210      */
00211     bool set_tx_gain(double gain);
00212 
00213     //! return minimum Tx gain 
00214     double tx_gain_min();
00215 
00216     //! return maximum Tx gain 
00217     double tx_gain_max();
00218 
00219     //! return Tx gain db_per_step
00220     double tx_gain_db_per_step();
00221 
00222     /*
00223      * \brief Set transmit daughterboard LO offset frequency
00224      */
00225     bool set_tx_lo_offset(double frequency);
00226 
00227     /*!
00228      * Set transmitter center frequency
00229      */
00230     bool set_tx_center_freq(double frequency, tune_result *result);
00231 
00232     //! return minimum Tx center frequency
00233     double tx_freq_min();
00234 
00235     //! return maximum Tx center frequency
00236     double tx_freq_max();
00237 
00238     /*!
00239      * Set transmitter sample rate interpolation
00240      */
00241     bool set_tx_interp(int interpolation_factor);
00242 
00243     //! Return current interpolation factor
00244     int tx_interp();
00245 
00246     /*
00247      * \brief Calculate default scale_iq for given interpolation rate
00248      */
00249     void default_tx_scale_iq(int interpolation_factor, int *scale_i, int *scale_q);
00250 
00251     /*!
00252      * Set transmit IQ magnitude scaling
00253      */
00254     bool set_tx_scale_iq(int scale_i, int scale_q);
00255 
00256     /*!
00257      * Set transmit sample format
00258      *   
00259      *    domain: complex or real
00260      *      type: floating, fixed point, or raw
00261      *     depth: bits per sample
00262      *
00263      * Sets format over the wire for samples to USRP2.
00264      */
00265     // bool set_tx_format(...);
00266 
00267     /*!
00268      * \brief transmit complex<float> samples to USRP2
00269      *
00270      * \param channel specifies the channel to send them to
00271      * \param samples are the samples to transmit.  They should be in the range [-1.0, +1.0]
00272      * \param nsamples is the number of samples to transmit
00273      * \param metadata provides the timestamp and flags
00274      *
00275      * The complex<float> samples are converted to the appropriate 
00276      * "on the wire" representation, depending on the current USRP2
00277      * configuration.  Typically, this is big-endian 16-bit I & Q.
00278      */
00279     bool tx_32fc(unsigned int channel,
00280                  const std::complex<float> *samples,
00281                  size_t nsamples,
00282                  const tx_metadata *metadata);
00283 
00284     /*!
00285      * \brief transmit complex<int16_t> samples to USRP2
00286      *
00287      * \param channel specifies the channel to send them to
00288      * \param samples are the samples to transmit
00289      * \param nsamples is the number of samples to transmit
00290      * \param metadata provides the timestamp and flags
00291      *
00292      * The complex<int16_t> samples are converted to the appropriate
00293      * "on the wire" representation, depending on the current USRP2
00294      * configuration.  Typically, this is big-endian 16-bit I & Q.
00295      */
00296     bool tx_16sc(unsigned int channel,
00297                  const std::complex<int16_t> *samples,
00298                  size_t nsamples,
00299                  const tx_metadata *metadata);
00300 
00301     /*!
00302      * \brief transmit raw uint32_t data items to USRP2
00303      *
00304      * The caller is responsible for ensuring that the items are
00305      * formatted appropriately for the USRP2 and its configuration.
00306      * This method is used primarily by the system itself.  Users
00307      * should call tx_32fc or tx_16sc instead.
00308      *
00309      * \param channel specifies the channel to send them to
00310      * \param items are the data items to transmit
00311      * \param nitems is the number of items to transmit
00312      * \param metadata provides the timestamp and flags
00313      */
00314     bool tx_raw(unsigned int channel,
00315                 const uint32_t *items,
00316                 size_t nitems,
00317                 const tx_metadata *metadata);
00318 
00319     /*
00320      * ----------------------------------------------------------------
00321      *  miscellaneous methods
00322      * ----------------------------------------------------------------
00323      */
00324 
00325     /*!
00326      * \brief MIMO configuration
00327      *
00328      * \param flags from usrp2_mimo_config.h
00329      *
00330      * <pre>
00331      *   one of these:
00332      *
00333      *     MC_WE_DONT_LOCK
00334      *     MC_WE_LOCK_TO_SMA
00335      *     MC_WE_LOCK_TO_MIMO
00336      *
00337      *   and optionally this:
00338      *
00339      *     MC_PROVIDE_CLK_TO_MIMO
00340      * </pre>
00341      */
00342     bool config_mimo(int flags);
00343 
00344 
00345     //! Get frequency of master oscillator in Hz
00346     bool fpga_master_clock_freq(long *freq);
00347 
00348     // Get Sampling rate of A/D converter in Hz
00349     bool adc_rate(long *rate);
00350 
00351     // Get Sampling rate of D/A converter in Hz
00352     bool dac_rate(long *rate);
00353 
00354     /*!
00355      * \brief Get Tx daughterboard ID
00356      *
00357      * \param[out] dbid returns the daughterboard id.
00358      *
00359      * daughterboard id >= 0 if successful, -1 if no daugherboard installed,
00360      * -2 if invalid EEPROM on daughterboard.
00361      */
00362     bool tx_daughterboard_id(int *dbid);
00363 
00364     /*!
00365      * \brief Get Rx daughterboard ID
00366      *
00367      * \param[out] dbid returns the daughterboard id.
00368      *
00369      * daughterboard id >= 0 if successful, -1 if no daugherboard installed,
00370      * -2 if invalid EEPROM on daughterboard.
00371      */
00372     bool rx_daughterboard_id(int *dbid);
00373 
00374     /*
00375      * ----------------------------------------------------------------
00376      *  Low level methods
00377      * ----------------------------------------------------------------
00378      */
00379 
00380     /*!
00381      * Burn new mac address into EEPROM on USRP2
00382      *
00383      * \param new_addr  Network mac address, e.g., "01:23:45:67:89:ab" or "89:ab".
00384      *                  If \p addr is HH:HH, it's treated as if it were 00:50:c2:85:HH:HH
00385      */
00386     bool burn_mac_addr(const std::string &new_addr);
00387 
00388     /*!
00389      * Reset master time to 0 at next PPS edge
00390      */
00391     bool sync_to_pps();
00392 
00393     /*!
00394      * Reset master time to 0 at every PPS edge
00395      */
00396     bool sync_every_pps(bool enable);
00397 
00398     /*!
00399      * Read memory from Wishbone bus as 32-bit words.  Handles endian swapping if needed.
00400      *
00401      * \param addr      32-bit aligned address.  Only the lower 16-bits are significant.
00402      * \param words     Number of 32-bit words
00403      * 
00404      * \returns         Vector of 32-bit read values
00405      *
00406      * WARNING: Attempts to read memory from addresses that do not correspond to RAM or
00407      * memory-mapped peripherals may cause the USRP2 to hang, requiring a power cycle.
00408      * 
00409      */
00410     std::vector<uint32_t> peek32(uint32_t addr, uint32_t words);
00411 
00412     /*!
00413      * Write memory to Wishbone bus as 32-bit words.  Handles endian swapping if needed.
00414      *
00415      * \param addr      32-bit aligned address.  Only the lower 16-bits are significant
00416      * \param data      Vector of 32-bit values to write.
00417      *
00418      * \returns true iff successful
00419      *
00420      * WARNING: Attempts to read memory from addresses that do not correspond to RAM or
00421      * memory-mapped peripherals may cause the USRP2 to hang, requiring a power cycle.
00422      * 
00423      */
00424     bool poke32(uint32_t addr, const std::vector<uint32_t> &data);
00425 
00426     /*!
00427      * Set daughterboard GPIO data direction register.
00428      *
00429      * \param bank      GPIO_TX_BANK or GPIO_RX_BANK
00430      * \param value     16-bits, 0=FPGA input, 1=FPGA output
00431      * \param mask      16-bits, 0=ignore, 1=set
00432      *
00433      * \returns true iff successful
00434      *
00435      * WARNING: Improper usage of this function may result in damage to the USRP2
00436      *
00437      */
00438     bool set_gpio_ddr(int bank, uint16_t value, uint16_t mask);
00439 
00440     /*!
00441      * Set daughterboard GPIO output selection register.  For those GPIO pins that
00442      * are configured as outputs in the DDR, this settings configures the source
00443      * of the pin value.
00444      *
00445      * \param bank      GPIO_TX_BANK or GPIO_RX_BANK
00446      * \param sels      Exactly 16 character MSB->LSB string. For each position:
00447      *                    '.' = ignore this bit, i.e., leave current value
00448      *                    'a' = Output ATR value
00449      *                    's' = Output host software controlled value
00450      *                    '0' = Output FPGA debug bus 0 value
00451      *                    '1' = Output FPGA debug bus 1 value
00452      *
00453      * \returns true iff successful
00454      *
00455      * WARNING: Improper usage of this function may result in damage to the USRP2
00456      *
00457      */
00458     bool set_gpio_sels(int bank, std::string sels);
00459 
00460     /*!
00461      * Set daughterboard GPIO pin values.
00462      *
00463      * \param bank     GPIO_TX_BANK or GPIO_RX_BANK
00464      * \param value    16 bits, 0=low, 1=high
00465      * \param mask     16 bits, 0=ignore, 1=set
00466      *
00467      * \returns true iff successful
00468      *
00469      * WARNING: Improper usage of this function may result in damage to the USRP2
00470      *
00471      */
00472     bool write_gpio(int bank, uint16_t value, uint16_t mask);
00473 
00474     /*!
00475      * Read daughterboard GPIO pin values
00476      *
00477      * \param bank     GPIO_TX_BANK or GPIO_RX_BANK
00478      * \param value    pointer to uint16_t to hold read results
00479      *
00480      * \returns true iff successful
00481      *
00482      */
00483     bool read_gpio(int bank, uint16_t *value);
00484 
00485     /*!
00486      * Set GPIO streaming mode
00487      *
00488      * Individually enables streaming GPIO pins through LSBs of DSP
00489      * samples.
00490      *
00491      * On receive, io_rx[15] replaces I[0], io_rx[14] replaces Q[0]
00492      * On transmit, I[0] maps to io_tx[15], Q[0] maps to io_tx[14]
00493      * (Transmit streaming is not yet implemented.)
00494      *
00495      * The selected GPIO pins must have been set as inputs or outputs
00496      * and, for transmit, set to software control.
00497      *
00498      * When enabled, the replaced DSP sample LSBs become 0.
00499      *
00500      * \param bank     GPIO_TX_BANK or GPIO_RX_BANK
00501      * \param enable   enable[0] controls I channel LSB
00502      *                 enable[1] controls Q channel LSB
00503      *
00504      * \returns true iff successful
00505      *
00506      * WARNING: Improper usage of this function may result in damage to the USRP2
00507      *
00508      */
00509     bool enable_gpio_streaming(int bank, int enable);
00510 
00511 #if 0   // not yet implemented
00512     /*!
00513      * \brief Write EEPROM on motherboard or any daughterboard.
00514      * \param i2c_addr          I2C bus address of EEPROM
00515      * \param eeprom_offset     byte offset in EEPROM to begin writing
00516      * \param buf               the data to write
00517      * \returns true iff sucessful
00518      */
00519     bool write_eeprom (int i2c_addr, int eeprom_offset, const std::string &buf);
00520 
00521     /*!
00522      * \brief Read EEPROM on motherboard or any daughterboard.
00523      * \param i2c_addr          I2C bus address of EEPROM
00524      * \param eeprom_offset     byte offset in EEPROM to begin reading
00525      * \param len               number of bytes to read
00526      * \returns the data read if successful, else a zero length string.
00527      */
00528     std::string read_eeprom (int i2c_addr, int eeprom_offset, int len);
00529 
00530     /*!
00531      * \brief Write to I2C peripheral
00532      * \param i2c_addr          I2C bus address (7-bits)
00533      * \param buf               the data to write
00534      * \returns true iff successful
00535      * Writes are limited to a maximum of of 64 bytes.
00536      */
00537     bool write_i2c (int i2c_addr, const std::string &buf);
00538 
00539     /*!
00540      * \brief Read from I2C peripheral
00541      * \param i2c_addr          I2C bus address (7-bits)
00542      * \param len               number of bytes to read
00543      * \returns the data read if successful, else a zero length string.
00544      * Reads are limited to a maximum of 64 bytes.
00545      */
00546     std::string read_i2c (int i2c_addr, int len);
00547 
00548     /*!
00549      * \brief Write data to SPI bus peripheral.
00550      *
00551      * \param optional_header   0,1 or 2 bytes to write before buf.
00552      * \param enables           bitmask of peripherals to write. See usrp_spi_defs.h
00553      * \param format            transaction format.  See usrp_spi_defs.h SPI_FMT_*
00554      * \param buf               the data to write
00555      * \returns true iff successful
00556      * Writes are limited to a maximum of 64 bytes.
00557      *
00558      * If \p format specifies that optional_header bytes are present, they are
00559      * written to the peripheral immediately prior to writing \p buf.
00560      */
00561     bool write_spi (int optional_header, int enables, int format, const std::string &buf);
00562 
00563     /*
00564      * \brief Read data from SPI bus peripheral.
00565      *
00566      * \param optional_header   0,1 or 2 bytes to write before buf.
00567      * \param enables           bitmask of peripheral to read. See usrp_spi_defs.h
00568      * \param format            transaction format.  See usrp_spi_defs.h SPI_FMT_*
00569      * \param len               number of bytes to read.  Must be in [0,64].
00570      * \returns the data read if sucessful, else a zero length string.
00571      *
00572      * Reads are limited to a maximum of 64 bytes.
00573      *
00574      * If \p format specifies that optional_header bytes are present, they
00575      * are written to the peripheral first.  Then \p len bytes are read from
00576      * the peripheral and returned.
00577      */
00578     std::string read_spi (int optional_header, int enables, int format, int len);
00579 #endif
00580 
00581 
00582     class impl;         // implementation details
00583 
00584   private:
00585     // Static function to retrieve or create usrp2 instance
00586     static sptr find_existing_or_make_new(const std::string &ifc, props *p, size_t rx_bufsize);
00587 
00588     // Only class members can instantiate this class
00589     usrp2(const std::string &ifc, props *p, size_t rx_bufsize);
00590   
00591     // All private state is held in opaque pointer
00592     std::auto_ptr<impl> d_impl;
00593   };
00594 
00595 };
00596 
00597 std::ostream& operator<<(std::ostream &os, const usrp2::props &x);
00598 
00599 
00600 #endif /* INCLUDED_USRP2_H */

Generated on Wed Jul 29 07:24:34 2009 for GNU Radio 3.2.2 C++ API by  doxygen 1.5.8