aboutsummaryrefslogtreecommitdiffstats
path: root/Transceiver52M/device/usrp1
diff options
context:
space:
mode:
Diffstat (limited to 'Transceiver52M/device/usrp1')
-rw-r--r--Transceiver52M/device/usrp1/Makefile.am10
-rw-r--r--Transceiver52M/device/usrp1/USRPDevice.cpp648
-rw-r--r--Transceiver52M/device/usrp1/USRPDevice.h204
3 files changed, 862 insertions, 0 deletions
diff --git a/Transceiver52M/device/usrp1/Makefile.am b/Transceiver52M/device/usrp1/Makefile.am
new file mode 100644
index 0000000..d99874a
--- /dev/null
+++ b/Transceiver52M/device/usrp1/Makefile.am
@@ -0,0 +1,10 @@
+include $(top_srcdir)/Makefile.common
+
+AM_CPPFLAGS = -Wall $(STD_DEFINES_AND_INCLUDES) -I${srcdir}/..
+AM_CXXFLAGS = -lpthread $(LIBOSMOCORE_CFLAGS) $(LIBOSMOCTRL_CFLAGS) $(LIBOSMOVTY_CFLAGS) $(USRP_CFLAGS)
+
+noinst_HEADERS = USRPDevice.h
+
+noinst_LTLIBRARIES = libdevice.la
+
+libdevice_la_SOURCES = USRPDevice.cpp
diff --git a/Transceiver52M/device/usrp1/USRPDevice.cpp b/Transceiver52M/device/usrp1/USRPDevice.cpp
new file mode 100644
index 0000000..f7f24e9
--- /dev/null
+++ b/Transceiver52M/device/usrp1/USRPDevice.cpp
@@ -0,0 +1,648 @@
+/*
+* Copyright 2008, 2009 Free Software Foundation, Inc.
+*
+* This software is distributed under the terms of the GNU Affero Public License.
+* See the COPYING file in the main directory for details.
+*
+* This use of this software may be subject to additional restrictions.
+* See the LEGAL file in the main directory for details.
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU Affero 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 Affero General Public License for more details.
+
+ You should have received a copy of the GNU Affero General Public License
+ along with this program. If not, see <http://www.gnu.org/licenses/>.
+
+*/
+
+
+/*
+ Compilation Flags
+
+ SWLOOPBACK compile for software loopback testing
+*/
+
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "Logger.h"
+#include "Threads.h"
+#include "USRPDevice.h"
+
+#ifdef HAVE_CONFIG_H
+#include "config.h"
+#endif
+
+using namespace std;
+
+enum dboardConfigType {
+ TXA_RXB,
+ TXB_RXA,
+ TXA_RXA,
+ TXB_RXB
+};
+
+#ifdef SINGLEDB
+const dboardConfigType dboardConfig = TXA_RXA;
+#else
+const dboardConfigType dboardConfig = TXA_RXB;
+#endif
+
+const double USRPDevice::masterClockRate = 52.0e6;
+
+USRPDevice::USRPDevice(size_t sps)
+{
+ LOG(INFO) << "creating USRP device...";
+
+ this->sps = sps;
+ decimRate = (unsigned int) round(masterClockRate/((GSMRATE) * (double) sps));
+ actualSampleRate = masterClockRate/decimRate;
+ rxGain = 0;
+
+ /*
+ * Undetermined delay b/w ping response timestamp and true
+ * receive timestamp. Values are empirically measured. With
+ * split sample rate Tx/Rx - 4/1 sps we need to need to
+ * compensate for advance rather than delay.
+ */
+ if (sps == 1)
+ pingOffset = 272;
+ else if (sps == 4)
+ pingOffset = 269 - 7500;
+ else
+ pingOffset = 0;
+
+#ifdef SWLOOPBACK
+ samplePeriod = 1.0e6/actualSampleRate;
+ loopbackBufferSize = 0;
+ gettimeofday(&lastReadTime,NULL);
+ firstRead = false;
+#endif
+}
+
+int USRPDevice::open(const std::string &, int, bool)
+{
+ writeLock.unlock();
+
+ LOG(INFO) << "opening USRP device..";
+#ifndef SWLOOPBACK
+ string rbf = "std_inband.rbf";
+ //string rbf = "inband_1rxhb_1tx.rbf";
+ m_uRx.reset();
+ if (!skipRx) {
+ try {
+ m_uRx = usrp_standard_rx_sptr(usrp_standard_rx::make(
+ 0, decimRate * sps, 1, -1,
+ usrp_standard_rx::FPGA_MODE_NORMAL,
+ 1024, 16 * 8, rbf));
+ m_uRx->set_fpga_master_clock_freq(masterClockRate);
+ }
+
+ catch(...) {
+ LOG(ALERT) << "make failed on Rx";
+ m_uRx.reset();
+ return -1;
+ }
+
+ if (m_uRx->fpga_master_clock_freq() != masterClockRate)
+ {
+ LOG(ALERT) << "WRONG FPGA clock freq = " << m_uRx->fpga_master_clock_freq()
+ << ", desired clock freq = " << masterClockRate;
+ m_uRx.reset();
+ return -1;
+ }
+ }
+
+ try {
+ m_uTx = usrp_standard_tx_sptr(usrp_standard_tx::make(
+ 0, decimRate * 2, 1, -1,
+ 1024, 16 * 8, rbf));
+ m_uTx->set_fpga_master_clock_freq(masterClockRate);
+ }
+
+ catch(...) {
+ LOG(ALERT) << "make failed on Tx";
+ m_uTx.reset();
+ return -1;
+ }
+
+ if (m_uTx->fpga_master_clock_freq() != masterClockRate)
+ {
+ LOG(ALERT) << "WRONG FPGA clock freq = " << m_uTx->fpga_master_clock_freq()
+ << ", desired clock freq = " << masterClockRate;
+ m_uTx.reset();
+ return -1;
+ }
+
+ if (!skipRx) m_uRx->stop();
+ m_uTx->stop();
+
+#endif
+
+ switch (dboardConfig) {
+ case TXA_RXB:
+ txSubdevSpec = usrp_subdev_spec(0,0);
+ rxSubdevSpec = usrp_subdev_spec(1,0);
+ break;
+ case TXB_RXA:
+ txSubdevSpec = usrp_subdev_spec(1,0);
+ rxSubdevSpec = usrp_subdev_spec(0,0);
+ break;
+ case TXA_RXA:
+ txSubdevSpec = usrp_subdev_spec(0,0);
+ rxSubdevSpec = usrp_subdev_spec(0,0);
+ break;
+ case TXB_RXB:
+ txSubdevSpec = usrp_subdev_spec(1,0);
+ rxSubdevSpec = usrp_subdev_spec(1,0);
+ break;
+ default:
+ txSubdevSpec = usrp_subdev_spec(0,0);
+ rxSubdevSpec = usrp_subdev_spec(1,0);
+ }
+
+ m_dbTx = m_uTx->selected_subdev(txSubdevSpec);
+ m_dbRx = m_uRx->selected_subdev(rxSubdevSpec);
+
+ samplesRead = 0;
+ samplesWritten = 0;
+ started = false;
+
+ return NORMAL;
+}
+
+
+
+bool USRPDevice::start()
+{
+ LOG(INFO) << "starting USRP...";
+#ifndef SWLOOPBACK
+ if (!m_uRx && !skipRx) return false;
+ if (!m_uTx) return false;
+
+ if (!skipRx) m_uRx->stop();
+ m_uTx->stop();
+
+ writeLock.lock();
+ // power up and configure daughterboards
+ m_dbTx->set_enable(true);
+ m_uTx->set_mux(m_uTx->determine_tx_mux_value(txSubdevSpec));
+ m_uRx->set_mux(m_uRx->determine_rx_mux_value(rxSubdevSpec));
+
+ if (!m_dbRx->select_rx_antenna(1))
+ m_dbRx->select_rx_antenna(0);
+
+ writeLock.unlock();
+
+ // Set gains to midpoint
+ setTxGain((minTxGain() + maxTxGain()) / 2);
+ setRxGain((minRxGain() + maxRxGain()) / 2);
+
+ data = new short[currDataSize];
+ dataStart = 0;
+ dataEnd = 0;
+ timeStart = 0;
+ timeEnd = 0;
+ timestampOffset = 0;
+ latestWriteTimestamp = 0;
+ lastPktTimestamp = 0;
+ hi32Timestamp = 0;
+ isAligned = false;
+
+
+ if (!skipRx)
+ started = (m_uRx->start() && m_uTx->start());
+ else
+ started = m_uTx->start();
+ return started;
+#else
+ gettimeofday(&lastReadTime,NULL);
+ return true;
+#endif
+}
+
+bool USRPDevice::stop()
+{
+#ifndef SWLOOPBACK
+ if (!m_uRx) return false;
+ if (!m_uTx) return false;
+
+ delete[] currData;
+
+ started = !(m_uRx->stop() && m_uTx->stop());
+ return !started;
+#else
+ return true;
+#endif
+}
+
+double USRPDevice::maxTxGain()
+{
+ return m_dbTx->gain_max();
+}
+
+double USRPDevice::minTxGain()
+{
+ return m_dbTx->gain_min();
+}
+
+double USRPDevice::maxRxGain()
+{
+ return m_dbRx->gain_max();
+}
+
+double USRPDevice::minRxGain()
+{
+ return m_dbRx->gain_min();
+}
+
+double USRPDevice::setTxGain(double dB, size_t chan)
+{
+ if (chan) {
+ LOG(ALERT) << "Invalid channel " << chan;
+ return 0.0;
+ }
+
+ writeLock.lock();
+ if (dB > maxTxGain())
+ dB = maxTxGain();
+ if (dB < minTxGain())
+ dB = minTxGain();
+
+ LOG(NOTICE) << "Setting TX gain to " << dB << " dB.";
+
+ if (!m_dbTx->set_gain(dB))
+ LOG(ERR) << "Error setting TX gain";
+
+ writeLock.unlock();
+
+ return dB;
+}
+
+
+double USRPDevice::setRxGain(double dB, size_t chan)
+{
+ if (chan) {
+ LOG(ALERT) << "Invalid channel " << chan;
+ return 0.0;
+ }
+
+ dB = 47.0;
+
+ writeLock.lock();
+ if (dB > maxRxGain())
+ dB = maxRxGain();
+ if (dB < minRxGain())
+ dB = minRxGain();
+
+ LOG(NOTICE) << "Setting RX gain to " << dB << " dB.";
+
+ if (!m_dbRx->set_gain(dB))
+ LOG(ERR) << "Error setting RX gain";
+
+ writeLock.unlock();
+
+ return dB;
+}
+
+bool USRPDevice::setRxAntenna(const std::string &ant, size_t chan)
+{
+ if (chan >= rx_paths.size()) {
+ LOG(ALERT) << "Requested non-existent channel " << chan;
+ return false;
+ }
+ LOG(ALERT) << "Not implemented";
+ return true;
+}
+
+std::string USRPDevice::getRxAntenna(size_t chan)
+{
+ if (chan >= rx_paths.size()) {
+ LOG(ALERT) << "Requested non-existent channel " << chan;
+ return "";
+ }
+ LOG(ALERT) << "Not implemented";
+ return "";
+}
+
+bool USRPDevice::setTxAntenna(const std::string &ant, size_t chan)
+{
+ if (chan >= tx_paths.size()) {
+ LOG(ALERT) << "Requested non-existent channel " << chan;
+ return false;
+ }
+ LOG(ALERT) << "Not implemented";
+ return true;
+}
+
+std::string USRPDevice::getTxAntenna(size_t chan)
+{
+ if (chan >= tx_paths.size()) {
+ LOG(ALERT) << "Requested non-existent channel " << chan;
+ return "";
+ }
+ LOG(ALERT) << "Not implemented";
+ return "";
+}
+
+
+// NOTE: Assumes sequential reads
+int USRPDevice::readSamples(std::vector<short *> &bufs, int len, bool *overrun,
+ TIMESTAMP timestamp, bool *underrun, unsigned *RSSI)
+{
+#ifndef SWLOOPBACK
+ if (!m_uRx)
+ return 0;
+
+ short *buf = bufs[0];
+
+ timestamp += timestampOffset;
+
+ if (timestamp + len < timeStart) {
+ memset(buf,0,len*2*sizeof(short));
+ return len;
+ }
+
+ if (underrun) *underrun = false;
+
+ uint32_t readBuf[2000];
+
+ while (1) {
+ //guestimate USB read size
+ int readLen=0;
+ {
+ int numSamplesNeeded = timestamp + len - timeEnd;
+ if (numSamplesNeeded <=0) break;
+ readLen = 512 * ((int) ceil((float) numSamplesNeeded/126.0));
+ if (readLen > 8000) readLen= (8000/512)*512;
+ }
+
+ // read USRP packets, parse and save A/D data as needed
+ readLen = m_uRx->read((void *)readBuf,readLen,overrun);
+ for(int pktNum = 0; pktNum < (readLen/512); pktNum++) {
+ // tmpBuf points to start of a USB packet
+ uint32_t* tmpBuf = (uint32_t *) (readBuf+pktNum*512/4);
+ TIMESTAMP pktTimestamp = usrp_to_host_u32(tmpBuf[1]);
+ uint32_t word0 = usrp_to_host_u32(tmpBuf[0]);
+ uint32_t chan = (word0 >> 16) & 0x1f;
+ unsigned payloadSz = word0 & 0x1ff;
+ LOG(DEBUG) << "first two bytes: " << hex << word0 << " " << dec << pktTimestamp;
+
+ bool incrementHi32 = ((lastPktTimestamp & 0x0ffffffffll) > pktTimestamp);
+ if (incrementHi32 && (timeStart!=0)) {
+ LOG(DEBUG) << "high 32 increment!!!";
+ hi32Timestamp++;
+ }
+ pktTimestamp = (((TIMESTAMP) hi32Timestamp) << 32) | pktTimestamp;
+ lastPktTimestamp = pktTimestamp;
+
+ if (chan == 0x01f) {
+ // control reply, check to see if its ping reply
+ uint32_t word2 = usrp_to_host_u32(tmpBuf[2]);
+ if ((word2 >> 16) == ((0x01 << 8) | 0x02)) {
+ timestamp -= timestampOffset;
+ timestampOffset = pktTimestamp - pingTimestamp + pingOffset;
+ LOG(DEBUG) << "updating timestamp offset to: " << timestampOffset;
+ timestamp += timestampOffset;
+ isAligned = true;
+ }
+ continue;
+ }
+ if (chan != 0) {
+ LOG(DEBUG) << "chan: " << chan << ", timestamp: " << pktTimestamp << ", sz:" << payloadSz;
+ continue;
+ }
+ if ((word0 >> 28) & 0x04) {
+ if (underrun) *underrun = true;
+ LOG(DEBUG) << "UNDERRUN in TRX->USRP interface";
+ }
+ if (RSSI) *RSSI = (word0 >> 21) & 0x3f;
+
+ if (!isAligned) continue;
+
+ unsigned cursorStart = pktTimestamp - timeStart + dataStart;
+ while (cursorStart*2 > currDataSize) {
+ cursorStart -= currDataSize/2;
+ }
+ if (cursorStart*2 + payloadSz/2 > currDataSize) {
+ // need to circle around buffer
+ memcpy(data+cursorStart*2,tmpBuf+2,(currDataSize-cursorStart*2)*sizeof(short));
+ memcpy(data,tmpBuf+2+(currDataSize/2-cursorStart),payloadSz-(currDataSize-cursorStart*2)*sizeof(short));
+ }
+ else {
+ memcpy(data+cursorStart*2,tmpBuf+2,payloadSz);
+ }
+ if (pktTimestamp + payloadSz/2/sizeof(short) > timeEnd)
+ timeEnd = pktTimestamp+payloadSz/2/sizeof(short);
+
+ LOG(DEBUG) << "timeStart: " << timeStart << ", timeEnd: " << timeEnd << ", pktTimestamp: " << pktTimestamp;
+
+ }
+ }
+
+ // copy desired data to buf
+ unsigned bufStart = dataStart+(timestamp-timeStart);
+ if (bufStart + len < currDataSize/2) {
+ LOG(DEBUG) << "bufStart: " << bufStart;
+ memcpy(buf,data+bufStart*2,len*2*sizeof(short));
+ memset(data+bufStart*2,0,len*2*sizeof(short));
+ }
+ else {
+ LOG(DEBUG) << "len: " << len << ", currDataSize/2: " << currDataSize/2 << ", bufStart: " << bufStart;
+ unsigned firstLength = (currDataSize/2-bufStart);
+ LOG(DEBUG) << "firstLength: " << firstLength;
+ memcpy(buf,data+bufStart*2,firstLength*2*sizeof(short));
+ memset(data+bufStart*2,0,firstLength*2*sizeof(short));
+ memcpy(buf+firstLength*2,data,(len-firstLength)*2*sizeof(short));
+ memset(data,0,(len-firstLength)*2*sizeof(short));
+ }
+ dataStart = (bufStart + len) % (currDataSize/2);
+ timeStart = timestamp + len;
+
+ return len;
+
+#else
+ if (loopbackBufferSize < 2) return 0;
+ int numSamples = 0;
+ struct timeval currTime;
+ gettimeofday(&currTime,NULL);
+ double timeElapsed = (currTime.tv_sec - lastReadTime.tv_sec)*1.0e6 +
+ (currTime.tv_usec - lastReadTime.tv_usec);
+ if (timeElapsed < samplePeriod) {return 0;}
+ int numSamplesToRead = (int) floor(timeElapsed/samplePeriod);
+ if (numSamplesToRead < len) return 0;
+
+ if (numSamplesToRead > len) numSamplesToRead = len;
+ if (numSamplesToRead > loopbackBufferSize/2) {
+ firstRead =false;
+ numSamplesToRead = loopbackBufferSize/2;
+ }
+ memcpy(buf,loopbackBuffer,sizeof(short)*2*numSamplesToRead);
+ loopbackBufferSize -= 2*numSamplesToRead;
+ memcpy(loopbackBuffer,loopbackBuffer+2*numSamplesToRead,
+ sizeof(short)*loopbackBufferSize);
+ numSamples = numSamplesToRead;
+ if (firstRead) {
+ int new_usec = lastReadTime.tv_usec + (int) round((double) numSamplesToRead * samplePeriod);
+ lastReadTime.tv_sec = lastReadTime.tv_sec + new_usec/1000000;
+ lastReadTime.tv_usec = new_usec % 1000000;
+ }
+ else {
+ gettimeofday(&lastReadTime,NULL);
+ firstRead = true;
+ }
+ samplesRead += numSamples;
+
+ return numSamples;
+#endif
+}
+
+int USRPDevice::writeSamples(std::vector<short *> &bufs, int len,
+ bool *underrun, unsigned long long timestamp,
+ bool isControl)
+{
+ writeLock.lock();
+
+#ifndef SWLOOPBACK
+ if (!m_uTx)
+ return 0;
+
+ short *buf = bufs[0];
+
+ static uint32_t outData[128*20];
+
+ for (int i = 0; i < len*2; i++) {
+ buf[i] = host_to_usrp_short(buf[i]);
+ }
+
+ int numWritten = 0;
+ unsigned isStart = 1;
+ unsigned RSSI = 0;
+ unsigned CHAN = (isControl) ? 0x01f : 0x00;
+ len = len*2*sizeof(short);
+ int numPkts = (int) ceil((float)len/(float)504);
+ unsigned isEnd = (numPkts < 2);
+ uint32_t *outPkt = outData;
+ int pktNum = 0;
+ while (numWritten < len) {
+ // pkt is pointer to start of a USB packet
+ uint32_t *pkt = outPkt + pktNum*128;
+ isEnd = (len - numWritten <= 504);
+ unsigned payloadLen = ((len - numWritten) < 504) ? (len-numWritten) : 504;
+ pkt[0] = (isStart << 12 | isEnd << 11 | (RSSI & 0x3f) << 5 | CHAN) << 16 | payloadLen;
+ pkt[1] = timestamp & 0x0ffffffffll;
+ memcpy(pkt+2,buf+(numWritten/sizeof(short)),payloadLen);
+ numWritten += payloadLen;
+ timestamp += payloadLen/2/sizeof(short);
+ isStart = 0;
+ pkt[0] = host_to_usrp_u32(pkt[0]);
+ pkt[1] = host_to_usrp_u32(pkt[1]);
+ pktNum++;
+ }
+ m_uTx->write((const void*) outPkt,sizeof(uint32_t)*128*numPkts,NULL);
+
+ samplesWritten += len/2/sizeof(short);
+ writeLock.unlock();
+
+ return len/2/sizeof(short);
+#else
+ int retVal = len;
+ memcpy(loopbackBuffer+loopbackBufferSize,buf,sizeof(short)*2*len);
+ samplesWritten += retVal;
+ loopbackBufferSize += retVal*2;
+
+ return retVal;
+#endif
+}
+
+bool USRPDevice::updateAlignment(TIMESTAMP timestamp)
+{
+#ifndef SWLOOPBACK
+ short data[] = {0x00,0x02,0x00,0x00};
+ uint32_t *wordPtr = (uint32_t *) data;
+ *wordPtr = host_to_usrp_u32(*wordPtr);
+ bool tmpUnderrun;
+
+ std::vector<short *> buf(1, data);
+ if (writeSamples(buf, 1, &tmpUnderrun, timestamp & 0x0ffffffffll, true)) {
+ pingTimestamp = timestamp;
+ return true;
+ }
+ return false;
+#else
+ return true;
+#endif
+}
+
+#ifndef SWLOOPBACK
+bool USRPDevice::setTxFreq(double wFreq, size_t chan)
+{
+ usrp_tune_result result;
+
+ if (chan) {
+ LOG(ALERT) << "Invalid channel " << chan;
+ return false;
+ }
+
+ if (m_uTx->tune(txSubdevSpec.side, m_dbTx, wFreq, &result)) {
+ LOG(INFO) << "set TX: " << wFreq << std::endl
+ << " baseband freq: " << result.baseband_freq << std::endl
+ << " DDC freq: " << result.dxc_freq << std::endl
+ << " residual freq: " << result.residual_freq;
+ return true;
+ }
+ else {
+ LOG(ALERT) << "set TX: " << wFreq << "failed" << std::endl
+ << " baseband freq: " << result.baseband_freq << std::endl
+ << " DDC freq: " << result.dxc_freq << std::endl
+ << " residual freq: " << result.residual_freq;
+ return false;
+ }
+}
+
+bool USRPDevice::setRxFreq(double wFreq, size_t chan)
+{
+ usrp_tune_result result;
+
+ if (chan) {
+ LOG(ALERT) << "Invalid channel " << chan;
+ return false;
+ }
+
+ if (m_uRx->tune(0, m_dbRx, wFreq, &result)) {
+ LOG(INFO) << "set RX: " << wFreq << std::endl
+ << " baseband freq: " << result.baseband_freq << std::endl
+ << " DDC freq: " << result.dxc_freq << std::endl
+ << " residual freq: " << result.residual_freq;
+ return true;
+ }
+ else {
+ LOG(ALERT) << "set RX: " << wFreq << "failed" << std::endl
+ << " baseband freq: " << result.baseband_freq << std::endl
+ << " DDC freq: " << result.dxc_freq << std::endl
+ << " residual freq: " << result.residual_freq;
+ return false;
+ }
+
+}
+
+#else
+bool USRPDevice::setTxFreq(double wFreq) { return true;};
+bool USRPDevice::setRxFreq(double wFreq) { return true;};
+#endif
+
+RadioDevice *RadioDevice::make(size_t tx_sps, size_t rx_sps,
+ InterfaceType iface, size_t chans, double offset,
+ const std::vector<std::string>& tx_paths,
+ const std::vector<std::string>& rx_paths)
+{
+ return new USRPDevice(tx_sps);
+}
diff --git a/Transceiver52M/device/usrp1/USRPDevice.h b/Transceiver52M/device/usrp1/USRPDevice.h
new file mode 100644
index 0000000..f981643
--- /dev/null
+++ b/Transceiver52M/device/usrp1/USRPDevice.h
@@ -0,0 +1,204 @@
+/*
+* Copyright 2008 Free Software Foundation, Inc.
+*
+* This software is distributed under multiple licenses; see the COPYING file in the main directory for licensing information for this specific distribuion.
+*
+* This use of this software may be subject to additional restrictions.
+* See the LEGAL file in the main directory for details.
+
+ 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.
+
+*/
+
+#ifndef _USRP_DEVICE_H_
+#define _USRP_DEVICE_H_
+
+#ifdef HAVE_CONFIG_H
+#include "config.h"
+#endif
+
+#include "radioDevice.h"
+
+#include <usrp/usrp_standard.h>
+#include <usrp/usrp_bytesex.h>
+#include <usrp/usrp_prims.h>
+#include <sys/time.h>
+#include <math.h>
+#include <string>
+#include <iostream>
+
+#include <boost/shared_ptr.hpp>
+typedef boost::shared_ptr<usrp_standard_tx> usrp_standard_tx_sptr;
+typedef boost::shared_ptr<usrp_standard_rx> usrp_standard_rx_sptr;
+
+/** A class to handle a USRP rev 4, with a two RFX900 daughterboards */
+class USRPDevice: public RadioDevice {
+
+private:
+
+ static const double masterClockRate; ///< the USRP clock rate
+ double desiredSampleRate; ///< the desired sampling rate
+ usrp_standard_rx_sptr m_uRx; ///< the USRP receiver
+ usrp_standard_tx_sptr m_uTx; ///< the USRP transmitter
+
+ db_base_sptr m_dbRx; ///< rx daughterboard
+ db_base_sptr m_dbTx; ///< tx daughterboard
+ usrp_subdev_spec rxSubdevSpec;
+ usrp_subdev_spec txSubdevSpec;
+
+ int sps;
+ double actualSampleRate; ///< the actual USRP sampling rate
+ unsigned int decimRate; ///< the USRP decimation rate
+
+ unsigned long long samplesRead; ///< number of samples read from USRP
+ unsigned long long samplesWritten; ///< number of samples sent to USRP
+
+ bool started; ///< flag indicates USRP has started
+ bool skipRx; ///< set if USRP is transmit-only.
+
+ static const unsigned int currDataSize_log2 = 21;
+ static const unsigned long currDataSize = (1 << currDataSize_log2);
+ short *data;
+ unsigned long dataStart;
+ unsigned long dataEnd;
+ TIMESTAMP timeStart;
+ TIMESTAMP timeEnd;
+ bool isAligned;
+
+ Mutex writeLock;
+
+ short *currData; ///< internal data buffer when reading from USRP
+ TIMESTAMP currTimestamp; ///< timestamp of internal data buffer
+ unsigned currLen; ///< size of internal data buffer
+
+ TIMESTAMP timestampOffset; ///< timestamp offset b/w Tx and Rx blocks
+ TIMESTAMP latestWriteTimestamp; ///< timestamp of most recent ping command
+ TIMESTAMP pingTimestamp; ///< timestamp of most recent ping response
+
+ long long pingOffset;
+ unsigned long hi32Timestamp;
+ unsigned long lastPktTimestamp;
+
+ double rxGain;
+
+#ifdef SWLOOPBACK
+ short loopbackBuffer[1000000];
+ int loopbackBufferSize;
+ double samplePeriod;
+
+ struct timeval startTime;
+ struct timeval lastReadTime;
+ bool firstRead;
+#endif
+
+ public:
+
+ /** Object constructor */
+ USRPDevice(size_t sps);
+
+ /** Instantiate the USRP */
+ int open(const std::string &, int, bool);
+
+ /** Start the USRP */
+ bool start();
+
+ /** Stop the USRP */
+ bool stop();
+
+ /** Set priority not supported */
+ void setPriority(float prio = 0.5) { }
+
+ enum TxWindowType getWindowType() { return TX_WINDOW_USRP1; }
+
+ /**
+ Read samples from the USRP.
+ @param buf preallocated buf to contain read result
+ @param len number of samples desired
+ @param overrun Set if read buffer has been overrun, e.g. data not being read fast enough
+ @param timestamp The timestamp of the first samples to be read
+ @param underrun Set if USRP does not have data to transmit, e.g. data not being sent fast enough
+ @param RSSI The received signal strength of the read result
+ @return The number of samples actually read
+ */
+ int readSamples(std::vector<short *> &buf, int len, bool *overrun,
+ TIMESTAMP timestamp = 0xffffffff, bool *underrun = NULL,
+ unsigned *RSSI = NULL);
+ /**
+ Write samples to the USRP.
+ @param buf Contains the data to be written.
+ @param len number of samples to write.
+ @param underrun Set if USRP does not have data to transmit, e.g. data not being sent fast enough
+ @param timestamp The timestamp of the first sample of the data buffer.
+ @param isControl Set if data is a control packet, e.g. a ping command
+ @return The number of samples actually written
+ */
+ int writeSamples(std::vector<short *> &bufs, int len, bool *underrun,
+ TIMESTAMP timestamp = 0xffffffff, bool isControl = false);
+
+ /** Update the alignment between the read and write timestamps */
+ bool updateAlignment(TIMESTAMP timestamp);
+
+ /** Set the transmitter frequency */
+ bool setTxFreq(double wFreq, size_t chan = 0);
+
+ /** Set the receiver frequency */
+ bool setRxFreq(double wFreq, size_t chan = 0);
+
+ /** Returns the starting write Timestamp*/
+ TIMESTAMP initialWriteTimestamp(void) { return 20000;}
+
+ /** Returns the starting read Timestamp*/
+ TIMESTAMP initialReadTimestamp(void) { return 20000;}
+
+ /** returns the full-scale transmit amplitude **/
+ double fullScaleInputValue() {return 13500.0;}
+
+ /** returns the full-scale receive amplitude **/
+ double fullScaleOutputValue() {return 9450.0;}
+
+ /** sets the receive chan gain, returns the gain setting **/
+ double setRxGain(double dB, size_t chan = 0);
+
+ /** get the current receive gain */
+ double getRxGain(size_t chan = 0) { return rxGain; }
+
+ /** return maximum Rx Gain **/
+ double maxRxGain(void);
+
+ /** return minimum Rx Gain **/
+ double minRxGain(void);
+
+ /** sets the transmit chan gain, returns the gain setting **/
+ double setTxGain(double dB, size_t chan = 0);
+
+ /** return maximum Tx Gain **/
+ double maxTxGain(void);
+
+ /** return minimum Rx Gain **/
+ double minTxGain(void);
+
+ /** sets the RX path to use, returns true if successful and false otherwise */
+ bool setRxAntenna(const std::string &ant, size_t chan = 0);
+
+ /* return the used RX path */
+ std::string getRxAntenna(size_t chan = 0);
+
+ /** sets the RX path to use, returns true if successful and false otherwise */
+ bool setTxAntenna(const std::string &ant, size_t chan = 0);
+
+ /* return the used RX path */
+ std::string getTxAntenna(size_t chan = 0);
+
+ /** Return internal status values */
+ inline double getTxFreq(size_t chan = 0) { return 0; }
+ inline double getRxFreq(size_t chan = 0) { return 0; }
+ inline double getSampleRate() { return actualSampleRate; }
+ inline double numberRead() { return samplesRead; }
+ inline double numberWritten() { return samplesWritten; }
+
+ std::vector<std::string> tx_paths, rx_paths;
+};
+
+#endif // _USRP_DEVICE_H_