aboutsummaryrefslogtreecommitdiffstats
path: root/Transceiver52M/ms
diff options
context:
space:
mode:
authorEric <ewild@sysmocom.de>2022-06-06 00:48:09 +0200
committerEric <ewild@sysmocom.de>2022-07-11 20:33:37 +0200
commit935c8cb7c977d063f472a8be6b2b024593894b33 (patch)
tree0491d351924c0fb8b4674fa52a23b8b992922556 /Transceiver52M/ms
parentf590eeb436a208f2bb5bb931604dc18a243a6d7a (diff)
new mssynctoy
Diffstat (limited to 'Transceiver52M/ms')
-rw-r--r--Transceiver52M/ms/bladerf_specific.h482
-rw-r--r--Transceiver52M/ms/ms_commandhandler.cpp229
-rw-r--r--Transceiver52M/ms/ms_rx_burst.cpp211
-rw-r--r--Transceiver52M/ms/ms_rx_burst.h25
-rw-r--r--Transceiver52M/ms/ms_rx_lower.cpp330
-rw-r--r--Transceiver52M/ms/ms_rx_upper.cpp364
-rw-r--r--Transceiver52M/ms/ms_rx_upper.h121
-rw-r--r--Transceiver52M/ms/ms_state.h175
-rw-r--r--Transceiver52M/ms/syncthing.cpp332
-rw-r--r--Transceiver52M/ms/syncthing.h224
-rw-r--r--Transceiver52M/ms/uhd_specific.h274
11 files changed, 2767 insertions, 0 deletions
diff --git a/Transceiver52M/ms/bladerf_specific.h b/Transceiver52M/ms/bladerf_specific.h
new file mode 100644
index 0000000..fcfcc9c
--- /dev/null
+++ b/Transceiver52M/ms/bladerf_specific.h
@@ -0,0 +1,482 @@
+#pragma once
+
+/*
+ * (C) 2022 by sysmocom s.f.m.c. GmbH <info@sysmocom.de>
+ * All Rights Reserved
+ *
+ * Author: Eric Wild <ewild@sysmocom.de>
+ *
+ * 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/>.
+ *
+ */
+
+#include "itrq.h"
+#include <atomic>
+#include <complex>
+#include <cstdint>
+#include <functional>
+#include <iostream>
+#include <cassert>
+#include <cstring>
+
+#include <libbladeRF.h>
+#include <Timeval.h>
+#include <unistd.h>
+
+const size_t BLADE_BUFFER_SIZE = 1024 * 1;
+const size_t BLADE_NUM_BUFFERS = 32 * 1;
+const size_t NUM_TRANSFERS = 16 * 2;
+const int SAMPLE_SCALE_FACTOR = 15; // actually 16 but sigproc complains about clipping..
+
+template <typename Arg, typename... Args> void doPrint(std::ostream &out, Arg &&arg, Args &&...args)
+{
+ out << '(' << std::forward<Arg>(arg);
+ using expander = int[];
+ (void)expander{ 0, (void(out << ',' << std::forward<Args>(args)), 0)... };
+ out << ')' << std::endl;
+}
+
+template <class R, class... Args> using RvalFunc = R (*)(Args...);
+
+// specialisation for funcs which return a value
+template <class R, class... Args>
+R exec_and_check(RvalFunc<R, Args...> func, const char *fname, const char *finame, const char *funcname, int line,
+ Args... args)
+{
+ R rval = func(std::forward<Args>(args)...);
+ if (rval != 0) {
+ std::cerr << ((rval >= 0) ? "OK:" : bladerf_strerror(rval)) << ':' << finame << ':' << line << ':'
+ << funcname << ':' << fname;
+ doPrint(std::cerr, args...);
+ }
+ return rval;
+}
+
+// only macros can pass a func name string
+#define blade_check(func, ...) exec_and_check(func, #func, __FILE__, __FUNCTION__, __LINE__, __VA_ARGS__)
+
+#pragma pack(push, 1)
+using blade_sample_type = std::complex<int16_t>;
+enum class blade_speed_buffer_type { HS, SS };
+template <blade_speed_buffer_type T> struct blade_usb_message {
+ uint32_t reserved;
+ uint64_t ts;
+ uint32_t meta_flags;
+ blade_sample_type d[(T == blade_speed_buffer_type::SS ? 512 : 256) - 4];
+};
+
+static_assert(sizeof(blade_usb_message<blade_speed_buffer_type::SS>) == 2048, "blade buffer mismatch!");
+static_assert(sizeof(blade_usb_message<blade_speed_buffer_type::HS>) == 1024, "blade buffer mismatch!");
+template <unsigned int SZ, blade_speed_buffer_type T> struct blade_otw_buffer {
+ static_assert((SZ >= 2 && !(SZ % 2)), "min size is 2x usb buffer!");
+ blade_usb_message<T> m[SZ];
+ int actual_samples_per_msg()
+ {
+ return sizeof(blade_usb_message<T>::d) / sizeof(typeof(blade_usb_message<T>::d[0]));
+ }
+ int actual_samples_per_buffer()
+ {
+ return SZ * actual_samples_per_msg();
+ }
+ int samples_per_buffer()
+ {
+ return SZ * sizeof(blade_usb_message<T>) / sizeof(typeof(blade_usb_message<T>::d[0]));
+ }
+ int num_msgs_per_buffer()
+ {
+ return SZ;
+ }
+ auto get_first_ts()
+ {
+ return m[0].ts;
+ }
+ constexpr auto *getsampleoffset(int ofs)
+ {
+ auto full = ofs / actual_samples_per_msg();
+ auto rem = ofs % actual_samples_per_msg();
+ return &m[full].d[rem];
+ }
+ int readall(blade_sample_type *outaddr)
+ {
+ blade_sample_type *addr = outaddr;
+ for (int i = 0; i < SZ; i++) {
+ memcpy(addr, &m[i].d[0], actual_samples_per_msg() * sizeof(blade_sample_type));
+ addr += actual_samples_per_msg();
+ }
+ return actual_samples_per_buffer();
+ }
+ int read_n(blade_sample_type *outaddr, int start, int num)
+ {
+ assert((start + num) <= actual_samples_per_buffer());
+ assert(start >= 0);
+
+ if (!num)
+ return 0;
+
+ // which buffer?
+ int start_buf_idx = (start > 0) ? start / actual_samples_per_msg() : 0;
+ // offset from actual buffer start
+ auto start_offset_in_buf = (start - (start_buf_idx * actual_samples_per_msg()));
+ auto samp_rem_in_first_buf = actual_samples_per_msg() - start_offset_in_buf;
+ auto remaining_first_buf = num > samp_rem_in_first_buf ? samp_rem_in_first_buf : num;
+
+ memcpy(outaddr, &m[start_buf_idx].d[start_offset_in_buf],
+ remaining_first_buf * sizeof(blade_sample_type));
+ outaddr += remaining_first_buf;
+
+ auto remaining = num - remaining_first_buf;
+
+ if (!remaining)
+ return num;
+
+ start_buf_idx++;
+
+ auto rem_full_bufs = remaining / actual_samples_per_msg();
+ remaining -= rem_full_bufs * actual_samples_per_msg();
+
+ for (int i = 0; i < rem_full_bufs; i++) {
+ memcpy(outaddr, &m[start_buf_idx++].d[0], actual_samples_per_msg() * sizeof(blade_sample_type));
+ outaddr += actual_samples_per_msg();
+ }
+
+ if (remaining)
+ memcpy(outaddr, &m[start_buf_idx].d[0], remaining * sizeof(blade_sample_type));
+ return num;
+ }
+ int write_n_burst(blade_sample_type *in, int num, uint64_t first_ts)
+ {
+ assert(num <= actual_samples_per_buffer());
+ int len_rem = num;
+ for (int i = 0; i < SZ; i++) {
+ m[i] = {};
+ m[i].ts = first_ts + i * actual_samples_per_msg();
+ if (len_rem) {
+ int max_to_copy =
+ len_rem > actual_samples_per_msg() ? actual_samples_per_msg() : len_rem;
+ memcpy(&m[i].d[0], in, max_to_copy * sizeof(blade_sample_type));
+ len_rem -= max_to_copy;
+ in += actual_samples_per_msg();
+ }
+ }
+ return num;
+ }
+};
+#pragma pack(pop)
+
+template <unsigned int SZ, blade_speed_buffer_type T> struct blade_otw_buffer_helper {
+ static_assert((SZ >= 1024 && ((SZ & (SZ - 1)) == 0)), "only buffer size multiples of 1024 allowed!");
+ static blade_otw_buffer<SZ / 512, T> x;
+};
+
+using dev_buf_t = typeof(blade_otw_buffer_helper<BLADE_BUFFER_SIZE, blade_speed_buffer_type::SS>::x);
+// using buf_in_use = blade_otw_buffer<2, blade_speed_buffer_type::SS>;
+using bh_fn_t = std::function<int(dev_buf_t *)>;
+
+template <typename T> struct blade_hw {
+ struct bladerf *dev;
+ struct bladerf_stream *rx_stream;
+ struct bladerf_stream *tx_stream;
+ // using pkt2buf = blade_otw_buffer<2, blade_speed_buffer_type::SS>;
+ using tx_buf_q_type = spsc_cond<BLADE_NUM_BUFFERS, dev_buf_t *, true, false>;
+ unsigned int rxFullScale, txFullScale;
+ int rxtxdelay;
+
+ float rxgain, txgain;
+
+ struct ms_trx_config {
+ int tx_freq;
+ int rx_freq;
+ int sample_rate;
+ int bandwidth;
+
+ public:
+ ms_trx_config() : tx_freq(881e6), rx_freq(926e6), sample_rate(((1625e3 / 6) * 4)), bandwidth(1e6)
+ {
+ }
+ } cfg;
+
+ struct buf_mgmt {
+ void **rx_samples;
+ void **tx_samples;
+ tx_buf_q_type bufptrqueue;
+
+ } buf_mgmt;
+
+ virtual ~blade_hw()
+ {
+ close_device();
+ }
+ blade_hw() : rxFullScale(2047), txFullScale(2047), rxtxdelay(-60)
+ {
+ }
+
+ void close_device()
+ {
+ if (dev) {
+ if (rx_stream) {
+ bladerf_deinit_stream(rx_stream);
+ }
+
+ if (tx_stream) {
+ bladerf_deinit_stream(tx_stream);
+ }
+
+ bladerf_enable_module(dev, BLADERF_MODULE_RX, false);
+ bladerf_enable_module(dev, BLADERF_MODULE_TX, false);
+
+ bladerf_close(dev);
+ dev = NULL;
+ }
+ }
+
+ int init_device(bh_fn_t rxh, bh_fn_t txh)
+ {
+ struct bladerf_rational_rate rate = { 0, static_cast<uint64_t>((1625e3 * 4)) * 64, 6 * 64 }, actual;
+
+ bladerf_log_set_verbosity(BLADERF_LOG_LEVEL_DEBUG);
+ bladerf_set_usb_reset_on_open(true);
+ blade_check(bladerf_open, &dev, "");
+ if (!dev) {
+ std::cerr << "open failed, device missing?" << std::endl;
+ return -1;
+ }
+ if (bladerf_device_speed(dev) != bladerf_dev_speed::BLADERF_DEVICE_SPEED_SUPER) {
+ std::cerr << "open failed, only superspeed (usb3) supported!" << std::endl;
+ return -1;
+ }
+
+ blade_check(bladerf_set_tuning_mode, dev, bladerf_tuning_mode::BLADERF_TUNING_MODE_FPGA);
+
+ bool is_locked;
+ blade_check(bladerf_set_pll_enable, dev, true);
+ blade_check(bladerf_set_pll_refclk, dev, 10000000UL);
+ for (int i = 0; i < 20; i++) {
+ usleep(50 * 1000);
+ bladerf_get_pll_lock_state(dev, &is_locked);
+
+ if (is_locked)
+ break;
+ }
+ if (!is_locked) {
+ std::cerr << "unable to lock refclk!" << std::endl;
+ return -1;
+ }
+
+ // bladerf_sample_rate r = (1625e3 * 4)/6, act;
+ // blade_check(bladerf_set_sample_rate,dev, BLADERF_CHANNEL_RX(0), r, &act);
+ // blade_check(bladerf_set_sample_rate,dev, BLADERF_CHANNEL_TX(0), r, &act);
+
+ // auto ratrate = (1625e3 * 4) / 6;
+ // rate.integer = (uint32_t)ratrate;
+ // rate.den = 10000;
+ // rate.num = (ratrate - rate.integer) * rate.den;
+
+ blade_check(bladerf_set_rational_sample_rate, dev, BLADERF_CHANNEL_RX(0), &rate, &actual);
+ blade_check(bladerf_set_rational_sample_rate, dev, BLADERF_CHANNEL_TX(0), &rate, &actual);
+
+ blade_check(bladerf_set_frequency, dev, BLADERF_CHANNEL_RX(0), (bladerf_frequency)cfg.rx_freq);
+ blade_check(bladerf_set_frequency, dev, BLADERF_CHANNEL_TX(0), (bladerf_frequency)cfg.tx_freq);
+
+ blade_check(bladerf_set_bandwidth, dev, BLADERF_CHANNEL_RX(0), (bladerf_bandwidth)cfg.bandwidth,
+ (bladerf_bandwidth *)NULL);
+ blade_check(bladerf_set_bandwidth, dev, BLADERF_CHANNEL_TX(0), (bladerf_bandwidth)cfg.bandwidth,
+ (bladerf_bandwidth *)NULL);
+
+ blade_check(bladerf_set_gain_mode, dev, BLADERF_CHANNEL_RX(0), BLADERF_GAIN_MGC);
+ // blade_check(bladerf_set_gain, dev, BLADERF_CHANNEL_RX(0), (bladerf_gain)30);
+ // blade_check(bladerf_set_gain, dev, BLADERF_CHANNEL_TX(0), (bladerf_gain)50);
+ usleep(1000);
+ blade_check(bladerf_enable_module, dev, BLADERF_MODULE_RX, true);
+ usleep(1000);
+ blade_check(bladerf_enable_module, dev, BLADERF_MODULE_TX, true);
+ usleep(1000);
+ blade_check(bladerf_init_stream, &rx_stream, dev, getrxcb(rxh), &buf_mgmt.rx_samples, BLADE_NUM_BUFFERS,
+ BLADERF_FORMAT_SC16_Q11_META, BLADE_BUFFER_SIZE, NUM_TRANSFERS, (void *)this);
+
+ blade_check(bladerf_init_stream, &tx_stream, dev, gettxcb(txh), &buf_mgmt.tx_samples, BLADE_NUM_BUFFERS,
+ BLADERF_FORMAT_SC16_Q11_META, BLADE_BUFFER_SIZE, NUM_TRANSFERS, (void *)this);
+
+ for (int i = 0; i < BLADE_NUM_BUFFERS; i++) {
+ auto cur_buffer = reinterpret_cast<tx_buf_q_type::elem_t *>(buf_mgmt.tx_samples);
+ buf_mgmt.bufptrqueue.spsc_push(&cur_buffer[i]);
+ }
+
+ setRxGain(20);
+ setTxGain(30);
+
+ usleep(1000);
+
+ // bladerf_set_stream_timeout(dev, BLADERF_TX, 4);
+ // bladerf_set_stream_timeout(dev, BLADERF_RX, 4);
+
+ return 0;
+ }
+
+ bool tuneTx(double freq, size_t chan = 0)
+ {
+ msleep(15);
+ blade_check(bladerf_set_frequency, dev, BLADERF_CHANNEL_TX(0), (bladerf_frequency)freq);
+ msleep(15);
+ return true;
+ };
+ bool tuneRx(double freq, size_t chan = 0)
+ {
+ msleep(15);
+ blade_check(bladerf_set_frequency, dev, BLADERF_CHANNEL_RX(0), (bladerf_frequency)freq);
+ msleep(15);
+ return true;
+ };
+ bool tuneRxOffset(double offset, size_t chan = 0)
+ {
+ return true;
+ };
+
+ double setRxGain(double dB, size_t chan = 0)
+ {
+ rxgain = dB;
+ msleep(15);
+ blade_check(bladerf_set_gain, dev, BLADERF_CHANNEL_RX(0), (bladerf_gain)dB);
+ msleep(15);
+ return dB;
+ };
+ double setTxGain(double dB, size_t chan = 0)
+ {
+ txgain = dB;
+ msleep(15);
+ blade_check(bladerf_set_gain, dev, BLADERF_CHANNEL_TX(0), (bladerf_gain)dB);
+ msleep(15);
+ return dB;
+ };
+ int setPowerAttenuation(int atten, size_t chan = 0)
+ {
+ return atten;
+ };
+
+ static void check_timestamp(dev_buf_t *rcd)
+ {
+ static bool first = true;
+ static uint64_t last_ts;
+ if (first) {
+ first = false;
+ last_ts = rcd->m[0].ts;
+ } else if (last_ts + rcd->actual_samples_per_buffer() != rcd->m[0].ts) {
+ std::cerr << "RX Overrun!" << last_ts << " " << rcd->actual_samples_per_buffer() << " "
+ << last_ts + rcd->actual_samples_per_buffer() << " " << rcd->m[0].ts << std::endl;
+ last_ts = rcd->m[0].ts;
+ } else {
+ last_ts = rcd->m[0].ts;
+ }
+ }
+
+ bladerf_stream_cb getrxcb(bh_fn_t rxbh)
+ {
+ // C cb -> no capture!
+ static auto rxbhfn = rxbh;
+ return [](struct bladerf *dev, struct bladerf_stream *stream, struct bladerf_metadata *meta,
+ void *samples, size_t num_samples, void *user_data) -> void * {
+ // struct blade_hw *trx = (struct blade_hw *)user_data;
+ static int to_skip = 0;
+ dev_buf_t *rcd = (dev_buf_t *)samples;
+
+ if (to_skip < 120) // prevents weird overflows on startup
+ to_skip++;
+ else {
+ check_timestamp(rcd);
+ rxbhfn(rcd);
+ }
+
+ return samples;
+ };
+ }
+ bladerf_stream_cb gettxcb(bh_fn_t txbh)
+ {
+ // C cb -> no capture!
+ static auto txbhfn = txbh;
+ return [](struct bladerf *dev, struct bladerf_stream *stream, struct bladerf_metadata *meta,
+ void *samples, size_t num_samples, void *user_data) -> void * {
+ struct blade_hw *trx = (struct blade_hw *)user_data;
+ auto ptr = reinterpret_cast<tx_buf_q_type::elem_t>(samples);
+
+ if (samples) // put buffer address back into queue, ready to be reused
+ trx->buf_mgmt.bufptrqueue.spsc_push(&ptr);
+
+ return BLADERF_STREAM_NO_DATA;
+ };
+ }
+
+ auto get_rx_burst_handler_fn(bh_fn_t burst_handler)
+ {
+ auto fn = [this] {
+ int status;
+ set_name_aff_sched("rxrun", 2, SCHED_FIFO, sched_get_priority_max(SCHED_FIFO) - 2);
+ status = bladerf_stream(rx_stream, BLADERF_RX_X1);
+ if (status < 0)
+ std::cerr << "rx stream error! " << bladerf_strerror(status) << std::endl;
+
+ return NULL;
+ };
+ return fn;
+ }
+ auto get_tx_burst_handler_fn(bh_fn_t burst_handler)
+ {
+ auto fn = [this] {
+ int status;
+ set_name_aff_sched("txrun", 2, SCHED_FIFO, sched_get_priority_max(SCHED_FIFO) - 1);
+ status = bladerf_stream(tx_stream, BLADERF_TX_X1);
+ if (status < 0)
+ std::cerr << "rx stream error! " << bladerf_strerror(status) << std::endl;
+
+ return NULL;
+ };
+ return fn;
+ }
+
+ void submit_burst_ts(blade_sample_type *buffer, int len, uint64_t ts)
+ {
+ //get empty bufer from list
+ tx_buf_q_type::elem_t rcd;
+
+ while (!buf_mgmt.bufptrqueue.spsc_pop(&rcd))
+ buf_mgmt.bufptrqueue.spsc_prep_pop();
+ assert(rcd != nullptr);
+
+ rcd->write_n_burst(buffer, len, ts + rxtxdelay); // blade xa4 specific delay!
+ // blade_check(bladerf_submit_stream_buffer_nb, tx_stream, (void *)rcd, 100U);
+ blade_check(bladerf_submit_stream_buffer_nb, tx_stream, (void *)rcd);
+ }
+
+ void set_name_aff_sched(const char *name, int cpunum, int schedtype, int prio)
+ {
+ pthread_setname_np(pthread_self(), name);
+
+ cpu_set_t cpuset;
+
+ CPU_ZERO(&cpuset);
+ CPU_SET(cpunum, &cpuset);
+
+ auto rv = pthread_setaffinity_np(pthread_self(), sizeof(cpuset), &cpuset);
+ if (rv < 0) {
+ std::cerr << name << " affinity: errreur! " << std::strerror(errno);
+ return exit(0);
+ }
+
+ sched_param sch_params;
+ sch_params.sched_priority = prio;
+ rv = pthread_setschedparam(pthread_self(), schedtype, &sch_params);
+ if (rv < 0) {
+ std::cerr << name << " sched: errreur! " << std::strerror(errno);
+ return exit(0);
+ }
+ }
+};
diff --git a/Transceiver52M/ms/ms_commandhandler.cpp b/Transceiver52M/ms/ms_commandhandler.cpp
new file mode 100644
index 0000000..13b95f9
--- /dev/null
+++ b/Transceiver52M/ms/ms_commandhandler.cpp
@@ -0,0 +1,229 @@
+/*
+ * (C) 2022 by sysmocom s.f.m.c. GmbH <info@sysmocom.de>
+ * All Rights Reserved
+ *
+ * Author: Eric Wild <ewild@sysmocom.de>
+ *
+ * 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/>.
+ *
+ */
+
+#include <radioInterface.h>
+#include "l1if.h"
+#include "ms_rx_upper.h"
+#include "syncthing.h"
+#include "ms_state.h"
+
+void upper_trx::driveControl()
+{
+#ifdef IPCIF
+ auto m = pop_c();
+ if (!m)
+ return;
+#else
+ TRX_C cmd;
+
+ socklen_t addr_len = sizeof(ctrlsrc);
+ int rdln = recvfrom(mCtrlSockets, (void *)cmd.cmd, sizeof(cmd) - 1, 0, &ctrlsrc, &addr_len);
+ if (rdln < 0 && errno == EAGAIN) {
+ std::cerr << "fuck, send ctrl?" << std::endl;
+ exit(0);
+ }
+
+ TRX_C *m = &cmd;
+#endif
+
+ auto response = (TRX_C *)malloc(sizeof(TRX_C));
+ response->cmd[0] = '\0';
+ commandhandler(m->cmd, response->cmd);
+#ifdef IPCIF
+ free(m);
+#endif
+ std::clog << "response is " << response->cmd << std::endl;
+#ifdef IPCIF
+ push_c(response);
+#else
+
+ int rv = sendto(mCtrlSockets, response, strlen(response->cmd) + 1, 0, &ctrlsrc, sizeof(struct sockaddr_in));
+ if (rv < 0) {
+ std::cerr << "fuck, rcv ctrl?" << std::endl;
+ exit(0);
+ }
+ free(response);
+
+#endif
+}
+
+void upper_trx::commandhandler(char *buffer, char *response)
+{
+ int MAX_PACKET_LENGTH = TRXC_BUF_SIZE;
+
+ char cmdcheck[4];
+ char command[MAX_PACKET_LENGTH];
+
+ sscanf(buffer, "%3s %s", cmdcheck, command);
+
+ if (strcmp(cmdcheck, "CMD") != 0) {
+ LOG(WARNING) << "bogus message on control interface";
+ return;
+ }
+ std::clog << "command is " << buffer << std::endl << std::flush;
+
+ if (strcmp(command, "MEASURE") == 0) {
+ msleep(100);
+ int freq;
+ sscanf(buffer, "%3s %s %d", cmdcheck, command, &freq);
+ sprintf(response, "RSP MEASURE 0 %d -80", freq);
+ } else if (strcmp(command, "ECHO") == 0) {
+ msleep(100);
+ sprintf(response, "RSP ECHO 0");
+ } else if (strcmp(command, "POWEROFF") == 0) {
+ set_ta(0);
+ // turn off transmitter/demod
+ sprintf(response, "RSP POWEROFF 0");
+ } else if (strcmp(command, "POWERON") == 0) {
+ // turn on transmitter/demod
+ if (!mTxFreq || !mRxFreq)
+ sprintf(response, "RSP POWERON 1");
+ else {
+ sprintf(response, "RSP POWERON 0");
+ if (!mOn) {
+ // Prepare for thread start
+ mPower = -20;
+ start_ms();
+
+ writeClockInterface();
+ mOn = true;
+ }
+ }
+ } else if (strcmp(command, "SETMAXDLY") == 0) {
+ //set expected maximum time-of-arrival
+ int maxDelay;
+ sscanf(buffer, "%3s %s %d", cmdcheck, command, &maxDelay);
+ mMaxExpectedDelay = maxDelay; // 1 GSM symbol is approx. 1 km
+ sprintf(response, "RSP SETMAXDLY 0 %d", maxDelay);
+ } else if (strcmp(command, "SETRXGAIN") == 0) {
+ //set expected maximum time-of-arrival
+ int newGain;
+ sscanf(buffer, "%3s %s %d", cmdcheck, command, &newGain);
+ newGain = setRxGain(newGain);
+ sprintf(response, "RSP SETRXGAIN 0 %d", newGain);
+ } else if (strcmp(command, "NOISELEV") == 0) {
+ if (mOn) {
+ float lev = 0; //mStates[chan].mNoiseLev;
+ sprintf(response, "RSP NOISELEV 0 %d", (int)round(20.0 * log10(rxFullScale / lev)));
+ } else {
+ sprintf(response, "RSP NOISELEV 1 0");
+ }
+ } else if (!strcmp(command, "SETPOWER")) {
+ // set output power in dB
+ int dbPwr;
+ sscanf(buffer, "%3s %s %d", cmdcheck, command, &dbPwr);
+ if (!mOn)
+ sprintf(response, "RSP SETPOWER 1 %d", dbPwr);
+ else {
+ mPower = dbPwr;
+ setPowerAttenuation(mPower);
+ sprintf(response, "RSP SETPOWER 0 %d", dbPwr);
+ }
+ } else if (!strcmp(command, "ADJPOWER")) {
+ // adjust power in dB steps
+ int dbStep;
+ sscanf(buffer, "%3s %s %d", cmdcheck, command, &dbStep);
+ if (!mOn)
+ sprintf(response, "RSP ADJPOWER 1 %d", mPower);
+ else {
+ mPower += dbStep;
+ setPowerAttenuation(mPower);
+ sprintf(response, "RSP ADJPOWER 0 %d", mPower);
+ }
+ } else if (strcmp(command, "RXTUNE") == 0) {
+ // tune receiver
+ int freqKhz;
+ sscanf(buffer, "%3s %s %d", cmdcheck, command, &freqKhz);
+ mRxFreq = freqKhz * 1e3;
+ if (!tuneRx(mRxFreq)) {
+ LOG(ALERT) << "RX failed to tune";
+ sprintf(response, "RSP RXTUNE 1 %d", freqKhz);
+ } else
+ sprintf(response, "RSP RXTUNE 0 %d", freqKhz);
+ } else if (strcmp(command, "TXTUNE") == 0) {
+ // tune txmtr
+ int freqKhz;
+ sscanf(buffer, "%3s %s %d", cmdcheck, command, &freqKhz);
+ mTxFreq = freqKhz * 1e3;
+ if (!tuneTx(mTxFreq)) {
+ LOG(ALERT) << "TX failed to tune";
+ sprintf(response, "RSP TXTUNE 1 %d", freqKhz);
+ } else
+ sprintf(response, "RSP TXTUNE 0 %d", freqKhz);
+ } else if (!strcmp(command, "SETTSC")) {
+ // set TSC
+ unsigned TSC;
+ sscanf(buffer, "%3s %s %d", cmdcheck, command, &TSC);
+ if (mOn)
+ sprintf(response, "RSP SETTSC 1 %d", TSC);
+ // else if (chan && (TSC != mTSC))
+ // sprintf(response, "RSP SETTSC 1 %d", TSC);
+ else {
+ mTSC = TSC;
+ //generateMidamble(rx_sps, TSC);
+ sprintf(response, "RSP SETTSC 0 %d", TSC);
+ }
+ } else if (!strcmp(command, "GETBSIC")) {
+ if (mBSIC < 0)
+ sprintf(response, "RSP GETBSIC 1");
+ else
+ sprintf(response, "RSP GETBSIC 0 %d", mBSIC);
+ } else if (strcmp(command, "SETSLOT") == 0) {
+ // set TSC
+ int corrCode;
+ int timeslot;
+ sscanf(buffer, "%3s %s %d %d", cmdcheck, command, &timeslot, &corrCode);
+ if ((timeslot < 0) || (timeslot > 7)) {
+ LOG(WARNING) << "bogus message on control interface";
+ sprintf(response, "RSP SETSLOT 1 %d %d", timeslot, corrCode);
+ return;
+ }
+ mStates.chanType[timeslot] = (ChannelCombination)corrCode;
+ mStates.setModulus(timeslot);
+ sprintf(response, "RSP SETSLOT 0 %d %d", timeslot, corrCode);
+ } else if (!strcmp(command, "SETRXMASK")) {
+ int slot;
+ unsigned long long mask;
+ sscanf(buffer, "%3s %s %d 0x%llx", cmdcheck, command, &slot, &mask);
+ if ((slot < 0) || (slot > 7)) {
+ sprintf(response, "RSP SETRXMASK 1");
+ } else {
+ mRxSlotMask[slot] = mask;
+ sprintf(response, "RSP SETRXMASK 0 %d 0x%llx", slot, mask);
+ }
+ } else if (!strcmp(command, "SYNC")) {
+ // msleep(10);
+ mStates.mode = trx_mode::TRX_MODE_MS_TRACK;
+ sprintf(response, "RSP SYNC 0");
+ mMaxExpectedDelay = 48;
+ // setRxGain(30);
+ // msleep(10);
+ } else if (!strcmp(command, "SETTA")) {
+ int ta;
+ sscanf(buffer, "%3s %s %d", cmdcheck, command, &ta);
+ set_ta(ta);
+ sprintf(response, "RSP SETTA 0 %d", ta);
+ } else {
+ LOG(WARNING) << "bogus command " << command << " on control interface.";
+ }
+
+ //mCtrlSockets[chan]->write(response, strlen(response) + 1);
+}
diff --git a/Transceiver52M/ms/ms_rx_burst.cpp b/Transceiver52M/ms/ms_rx_burst.cpp
new file mode 100644
index 0000000..999584d
--- /dev/null
+++ b/Transceiver52M/ms/ms_rx_burst.cpp
@@ -0,0 +1,211 @@
+/*
+ * (C) 2022 by sysmocom s.f.m.c. GmbH <info@sysmocom.de>
+ * All Rights Reserved
+ *
+ * Author: Eric Wild <ewild@sysmocom.de>
+ *
+ * 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/>.
+ *
+ */
+#include "syncthing.h"
+#include "sigProcLib.h"
+#include "signalVector.h"
+#include "grgsm_vitac/grgsm_vitac.h"
+extern "C" {
+#include "sch.h"
+}
+
+#if !defined(SYNCTHINGONLY) || !defined(NODAMNLOG)
+#define DBGLG(...) ms_trx::dummy_log()
+#else
+#define DBGLG(...) std::cerr
+#endif
+
+#if !defined(SYNCTHINGONLY)
+#define DBGLG2(...) ms_trx::dummy_log()
+#else
+#define DBGLG2(...) std::cerr
+#endif
+
+__attribute__((xray_always_instrument)) __attribute__((noinline)) static bool decode_sch(float *bits,
+ bool update_global_clock)
+{
+ struct sch_info sch;
+ ubit_t info[GSM_SCH_INFO_LEN];
+ sbit_t data[GSM_SCH_CODED_LEN];
+
+ float_to_sbit(&bits[3], &data[0], 62, 39);
+ float_to_sbit(&bits[106], &data[39], 62, 39);
+
+ if (!gsm_sch_decode(info, data)) {
+ gsm_sch_parse(info, &sch);
+
+ DBGLG() << "SCH : Decoded values" << std::endl;
+ DBGLG() << " BSIC: " << sch.bsic << std::endl;
+ DBGLG() << " TSC: " << (sch.bsic & 0x7) << std::endl;
+ DBGLG() << " T1 : " << sch.t1 << std::endl;
+ DBGLG() << " T2 : " << sch.t2 << std::endl;
+ DBGLG() << " T3p : " << sch.t3p << std::endl;
+ DBGLG() << " FN : " << gsm_sch_to_fn(&sch) << std::endl;
+ return true;
+ }
+ return false;
+}
+
+static void check_rcv_fn(GSM::Time t, bool first, unsigned int &lastfn, unsigned int &fnbm)
+{
+ if (first && t.TN() == 0) {
+ lastfn = t.FN();
+ fnbm = 1 << 0;
+ first = false;
+ }
+ if (!first && t.FN() != lastfn) {
+ if (fnbm != 255)
+ std::cerr << "rx " << lastfn << ":" << fnbm << " " << __builtin_popcount(fnbm) << std::endl;
+ lastfn = t.FN();
+ fnbm = 1 << t.TN();
+ }
+
+ fnbm |= 1 << t.TN();
+}
+
+__attribute__((xray_always_instrument)) __attribute__((noinline)) static void
+handle_it(one_burst &e, signalVector &burst, unsigned int tsc)
+{
+ memset(burst.begin(), 0, burst.size() * sizeof(std::complex<float>));
+ auto is_sch = gsm_sch_check_fn(e.gsmts.FN()) && e.gsmts.TN() == 0;
+ auto is_fcch = gsm_fcch_check_fn(e.gsmts.FN()) && e.gsmts.TN() == 0;
+
+ // if (is_sch)
+ // return;
+
+ if (is_fcch)
+ return;
+
+ if (is_sch) {
+ unsigned char outbin[148];
+ convert_and_scale_default<float, int16_t>(burst.begin(), e.burst, ONE_TS_BURST_LEN * 2);
+ std::stringstream dbgout;
+#if 0
+ {
+ struct estim_burst_params ebp;
+ auto rv2 = detectSCHBurst(burst, 4, 4, sch_detect_type::SCH_DETECT_FULL, &ebp);
+ auto bits = demodAnyBurst(burst, SCH, 4, &ebp);
+ // clamp_array(bits->begin(), 148, 1.5f);
+ for (auto &i : *bits)
+ i = (i > 0 ? 1 : -1);
+
+ auto rv = decode_sch(bits->begin(), false);
+ dbgout << "U DET@" << (rv2 ? "yes " : " ") << "Timing offset " << ebp.toa
+ << " symbols, DECODE: " << (rv ? "yes" : "---") << " ";
+
+ delete bits;
+ }
+#endif
+ {
+ convert_and_scale<float, float>(burst.begin(), burst.begin(), ONE_TS_BURST_LEN * 2,
+ 1.f / 32767.f);
+
+ std::complex<float> channel_imp_resp[CHAN_IMP_RESP_LENGTH * d_OSR];
+ auto ss = reinterpret_cast<std::complex<float> *>(burst.begin());
+ int d_c0_burst_start = get_sch_chan_imp_resp(ss, &channel_imp_resp[0]);
+ detect_burst(ss, &channel_imp_resp[0], d_c0_burst_start, outbin);
+
+ SoftVector bits;
+ bits.resize(148);
+ for (int i = 0; i < 148; i++) {
+ bits[i] = (!outbin[i]) < 1 ? -1 : 1;
+ }
+
+ auto rv = decode_sch(bits.begin(), false);
+ dbgout << "U SCH@"
+ << " " << e.gsmts.FN() << ":" << e.gsmts.TN() << " " << d_c0_burst_start
+ << " DECODE:" << (rv ? "yes" : "---") << std::endl;
+ }
+
+ DBGLG() << dbgout.str();
+ return;
+ }
+#if 1
+ convert_and_scale<float, int16_t>(burst.begin(), e.burst, ONE_TS_BURST_LEN * 2, 1.f / 2047.f);
+ // std::cerr << "@" << tsc << " " << e.gsmts.FN() << ":" << e.gsmts.TN() << " " << ebp.toa << " "
+ // << std::endl;
+
+ unsigned char outbin[148];
+ auto ss = reinterpret_cast<std::complex<float> *>(burst.begin());
+ float ncmax, dcmax;
+ std::complex<float> chan_imp_resp[CHAN_IMP_RESP_LENGTH * d_OSR], chan_imp_resp2[CHAN_IMP_RESP_LENGTH * d_OSR];
+ auto normal_burst_start = get_norm_chan_imp_resp(ss, &chan_imp_resp[0], &ncmax, tsc);
+ auto dummy_burst_start = get_norm_chan_imp_resp(ss, &chan_imp_resp2[0], &dcmax, TS_DUMMY);
+ auto is_nb = ncmax > dcmax;
+
+ DBGLG() << " U " << (is_nb ? "NB" : "DB") << "@ o nb: " << normal_burst_start << " o db: " << dummy_burst_start
+ << std::endl;
+
+ if (is_nb)
+ detect_burst(ss, &chan_imp_resp[0], normal_burst_start, outbin);
+ else
+ detect_burst(ss, &chan_imp_resp2[0], dummy_burst_start, outbin);
+ ;
+
+ auto bits = SoftVector(148);
+ for (int i = 0; i < 148; i++)
+ (bits)[i] = outbin[i] < 1 ? -1 : 1;
+
+#endif
+}
+
+__attribute__((xray_always_instrument)) __attribute__((noinline)) void rcv_bursts_test(rx_queue_t *q, unsigned int *tsc)
+{
+ static bool first = true;
+ unsigned int lastfn = 0;
+ unsigned int fnbm = 0;
+ signalVector burst(ONE_TS_BURST_LEN, 100, 100);
+
+ cpu_set_t cpuset;
+
+ CPU_ZERO(&cpuset);
+ CPU_SET(1, &cpuset);
+
+ auto rv = pthread_setaffinity_np(pthread_self(), sizeof(cpuset), &cpuset);
+ if (rv < 0) {
+ std::cerr << "affinity: errreur! " << std::strerror(errno);
+ exit(0);
+ }
+
+ int prio = sched_get_priority_max(SCHED_RR);
+ struct sched_param param;
+ param.sched_priority = prio;
+ rv = sched_setscheduler(0, SCHED_RR, &param);
+ if (rv < 0) {
+ std::cerr << "scheduler: errreur! " << std::strerror(errno);
+ exit(0);
+ }
+
+ while (1) {
+ one_burst e;
+ while (!q->spsc_pop(&e)) {
+ q->spsc_prep_pop();
+ }
+
+ check_rcv_fn(e.gsmts, first, lastfn, fnbm);
+
+ handle_it(e, burst, *tsc);
+
+ // rv = detectSCHBurst(*burst, 4, 4, sch_detect_type::SCH_DETECT_FULL, &ebp);
+ // if (rv > 0)
+ // std::cerr << "#" << e.gsmts.FN() << ":" << e.gsmts.TN() << " " << ebp.toa << std::endl;
+ // sched_yield();
+ }
+} \ No newline at end of file
diff --git a/Transceiver52M/ms/ms_rx_burst.h b/Transceiver52M/ms/ms_rx_burst.h
new file mode 100644
index 0000000..301ebcf
--- /dev/null
+++ b/Transceiver52M/ms/ms_rx_burst.h
@@ -0,0 +1,25 @@
+#pragma once
+/*
+ * (C) 2022 by sysmocom s.f.m.c. GmbH <info@sysmocom.de>
+ * All Rights Reserved
+ *
+ * Author: Eric Wild <ewild@sysmocom.de>
+ *
+ * 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/>.
+ *
+ */
+
+#include "syncthing.h"
+
+void rcv_bursts_test(rx_queue_t *q, unsigned int *tsc); \ No newline at end of file
diff --git a/Transceiver52M/ms/ms_rx_lower.cpp b/Transceiver52M/ms/ms_rx_lower.cpp
new file mode 100644
index 0000000..15e562c
--- /dev/null
+++ b/Transceiver52M/ms/ms_rx_lower.cpp
@@ -0,0 +1,330 @@
+/*
+ * (C) 2022 by sysmocom s.f.m.c. GmbH <info@sysmocom.de>
+ * All Rights Reserved
+ *
+ * Author: Eric Wild <ewild@sysmocom.de>
+ *
+ * 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/>.
+ *
+ */
+
+#include "sigProcLib.h"
+#include "signalVector.h"
+#include <atomic>
+#include <cassert>
+#include <complex>
+#include <iostream>
+#include <future>
+
+#include "syncthing.h"
+#include "grgsm_vitac/grgsm_vitac.h"
+
+extern "C" {
+#include "sch.h"
+}
+
+#ifdef LOG
+#undef LOG
+#endif
+
+#if !defined(SYNCTHINGONLY) //|| !defined(NODAMNLOG)
+#define DBGLG(...) ms_trx::dummy_log()
+#else
+#define DBGLG(...) std::cerr
+#endif
+
+#if !defined(SYNCTHINGONLY) || !defined(NODAMNLOG)
+#define DBGLG2(...) ms_trx::dummy_log()
+#else
+#define DBGLG2(...) std::cerr
+#endif
+
+#define PRINT_Q_OVERFLOW
+__attribute__((xray_always_instrument)) __attribute__((noinline)) bool ms_trx::decode_sch(float *bits,
+ bool update_global_clock)
+{
+ int fn;
+ struct sch_info sch;
+ ubit_t info[GSM_SCH_INFO_LEN];
+ sbit_t data[GSM_SCH_CODED_LEN];
+
+ float_to_sbit(&bits[3], &data[0], 62, 39);
+ float_to_sbit(&bits[106], &data[39], 62, 39);
+
+ if (!gsm_sch_decode(info, data)) {
+ gsm_sch_parse(info, &sch);
+
+ if (update_global_clock) {
+ DBGLG() << "SCH : Decoded values" << std::endl;
+ DBGLG() << " BSIC: " << sch.bsic << std::endl;
+ DBGLG() << " TSC: " << (sch.bsic & 0x7) << std::endl;
+ DBGLG() << " T1 : " << sch.t1 << std::endl;
+ DBGLG() << " T2 : " << sch.t2 << std::endl;
+ DBGLG() << " T3p : " << sch.t3p << std::endl;
+ DBGLG() << " FN : " << gsm_sch_to_fn(&sch) << std::endl;
+ }
+
+ fn = gsm_sch_to_fn(&sch);
+ if (fn < 0) { // how? wh?
+ DBGLG() << "SCH : Failed to convert FN " << std::endl;
+ return false;
+ }
+
+ if (update_global_clock) {
+ mBSIC = sch.bsic;
+ mTSC = sch.bsic & 0x7;
+ timekeeper.set(fn, 0);
+ // global_time_keeper.FN(fn);
+ // global_time_keeper.TN(0);
+ }
+#ifdef SYNCTHINGONLY
+ else {
+ int t3 = sch.t3p * 10 + 1;
+ if (t3 == 11) {
+ // timeslot hitter attempt @ fn 21 in mf
+ DBGLG2() << "sch @ " << t3 << std::endl;
+ auto e = GSM::Time(fn, 0);
+ e += 10;
+ ts_hitter_q.spsc_push(&e);
+ }
+ }
+#endif
+ // auto sch11 = gsm_sch_check_fn(fn + 11);
+ // DBGLG() << "next sch: "<< (sch11 ? "11":"10")<<" first ts " << first_sch_buf_rcv_ts << std::endl;
+ return true;
+ }
+ return false;
+}
+
+void ms_trx::maybe_update_gain(one_burst &brst)
+{
+ static_assert((sizeof(brst.burst) / sizeof(brst.burst[0])) == ONE_TS_BURST_LEN, "wtf, buffer size mismatch?");
+ const int avgburst_num = 8 * 20; // ~ 50*4.5ms = 90ms?
+ static_assert(avgburst_num * 577 > (50 * 1000), "can't update faster then blade wait time?");
+ const unsigned int rx_max_cutoff = (rxFullScale * 2) / 3;
+ static int gain_check = 0;
+ static float runmean = 0;
+ float sum = 0;
+ for (auto i : brst.burst)
+ sum += abs(i.real()) + abs(i.imag());
+ sum /= ONE_TS_BURST_LEN * 2;
+
+ runmean = gain_check ? (runmean * (gain_check + 2) - 1 + sum) / (gain_check + 2) : sum;
+
+ if (gain_check == avgburst_num - 1) {
+ DBGLG2() << "\x1B[32m #RXG \033[0m" << rxgain << " " << runmean << " " << sum << std::endl;
+ auto gainoffset = runmean < (rxFullScale / 4 ? 4 : 2);
+ gainoffset = runmean < (rxFullScale / 2 ? 2 : 1);
+ float newgain = runmean < rx_max_cutoff ? rxgain + gainoffset : rxgain - gainoffset;
+ // FIXME: gian cutoff
+ if (newgain != rxgain && newgain <= 60)
+ std::thread([this, newgain] { setRxGain(newgain); }).detach();
+ runmean = 0;
+ }
+ gain_check = (gain_check + 1) % avgburst_num;
+}
+
+bool ms_trx::handle_sch_or_nb(bool get_first_sch)
+{
+ one_burst brst;
+ auto current_gsm_time = timekeeper.gsmtime();
+ brst.gsmts = current_gsm_time;
+ memcpy(brst.burst, burst_copy_buffer, sizeof(blade_sample_type) * ONE_TS_BURST_LEN);
+ auto pushok = rxqueue.spsc_push(&brst);
+#ifdef PRINT_Q_OVERFLOW
+ if (!pushok)
+ std::cout << "F" << std::endl;
+#endif
+ if (do_auto_gain)
+ maybe_update_gain(brst);
+
+ // only continue for SCH, don't touch FCCH
+ auto is_sch = gsm_sch_check_fn(current_gsm_time.FN()) && current_gsm_time.TN() == 0;
+ auto is_fcch = gsm_fcch_check_fn(current_gsm_time.FN()) && current_gsm_time.TN() == 0;
+#pragma unused(is_fcch)
+
+ if (!is_sch) {
+ // sched_yield();
+ return false;
+ }
+ auto rv = handle_sch(false);
+ // sched_yield();
+ return rv;
+}
+
+float bernd[SCH_LEN_SPS * 2];
+
+bool ms_trx::handle_sch(bool is_first_sch_acq)
+{
+ struct estim_burst_params ebp;
+ auto current_gsm_time = timekeeper.gsmtime();
+ const auto buf_len = is_first_sch_acq ? SCH_LEN_SPS : ONE_TS_BURST_LEN;
+ const auto which_buffer = is_first_sch_acq ? first_sch_buf : burst_copy_buffer;
+
+ std::complex<float> channel_imp_resp[CHAN_IMP_RESP_LENGTH * d_OSR];
+ unsigned char outbin[148];
+ float max_corr = 0;
+ const auto ss = reinterpret_cast<std::complex<float> *>(&bernd[0]);
+ convert_and_scale<float, int16_t>(bernd, which_buffer, buf_len * 2, 1.f / 2047.f);
+
+ auto start = is_first_sch_acq ? get_sch_buffer_chan_imp_resp(ss, &channel_imp_resp[0], buf_len, &max_corr) :
+ get_sch_chan_imp_resp(ss, channel_imp_resp);
+ detect_burst(&ss[start], &channel_imp_resp[0], 0, outbin);
+
+ SoftVector bitss(148);
+ for (int i = 0; i < 148; i++) {
+ bitss[i] = (!outbin[i]) < 1 ? -1 : 1;
+ }
+
+ auto sch_decode_success = decode_sch(bitss.begin(), is_first_sch_acq);
+
+ if (sch_decode_success) {
+ const auto ts_offset_symb = 0;
+ if (is_first_sch_acq) {
+ // update ts to first sample in sch buffer, to allow delay calc for current ts
+ first_sch_ts_start = first_sch_buf_rcv_ts + start - (ts_offset_symb * 4);
+ } else if (abs(start) > 1) {
+ // continuous sch tracking, only update if off too much
+ temp_ts_corr_offset += -start;
+ std::cerr << "offs: " << start << " " << temp_ts_corr_offset << std::endl;
+ }
+
+ return true;
+ } else {
+ DBGLG2() << "L SCH : \x1B[31m decode fail \033[0m @ toa:" << start << " " << current_gsm_time.FN()
+ << ":" << current_gsm_time.TN() << std::endl;
+ }
+ return false;
+}
+
+__attribute__((xray_never_instrument)) SCH_STATE ms_trx::search_for_sch(dev_buf_t *rcd)
+{
+ static unsigned int sch_pos = 0;
+ if (sch_thread_done)
+ return SCH_STATE::FOUND;
+
+ if (rcv_done)
+ return SCH_STATE::SEARCHING;
+
+ auto to_copy = SCH_LEN_SPS - sch_pos;
+
+ if (SCH_LEN_SPS == to_copy) // first time
+ first_sch_buf_rcv_ts = rcd->get_first_ts();
+
+ if (!to_copy) {
+ sch_pos = 0;
+ rcv_done = true;
+ std::thread([this] {
+ set_name_aff_sched("sch_search", 1, SCHED_FIFO, sched_get_priority_max(SCHED_FIFO) - 5);
+
+ auto ptr = reinterpret_cast<const int16_t *>(first_sch_buf);
+ const auto target_val = rxFullScale / 8;
+ float sum = 0;
+ for (int i = 0; i < SCH_LEN_SPS * 2; i++)
+ sum += std::abs(ptr[i]);
+ sum /= SCH_LEN_SPS * 2;
+
+ //FIXME: arbitrary value, gain cutoff
+ if (sum > target_val || rxgain >= 60) // enough ?
+ sch_thread_done = this->handle_sch(true);
+ else {
+ std::cerr << "\x1B[32m #RXG \033[0m gain " << rxgain << " -> " << rxgain + 4
+ << " sample avg:" << sum << " target: >=" << target_val << std::endl;
+ setRxGain(rxgain + 4);
+ }
+
+ if (!sch_thread_done)
+ rcv_done = false; // retry!
+ return (bool)sch_thread_done;
+ }).detach();
+ }
+
+ auto spsmax = rcd->actual_samples_per_buffer();
+ if (to_copy > spsmax)
+ sch_pos += rcd->readall(first_sch_buf + sch_pos);
+ else
+ sch_pos += rcd->read_n(first_sch_buf + sch_pos, 0, to_copy);
+
+ return SCH_STATE::SEARCHING;
+}
+__attribute__((optnone)) void ms_trx::grab_bursts(dev_buf_t *rcd)
+{
+ // partial burst samples read from the last buffer
+ static int partial_rdofs = 0;
+ static bool first_call = true;
+ int to_skip = 0;
+
+ // round up to next burst by calculating the time between sch detection and now
+ if (first_call) {
+ const auto next_burst_start = rcd->get_first_ts() - first_sch_ts_start;
+ const auto fullts = next_burst_start / ONE_TS_BURST_LEN;
+ const auto fracts = next_burst_start % ONE_TS_BURST_LEN;
+ to_skip = ONE_TS_BURST_LEN - fracts;
+
+ for (int i = 0; i < fullts; i++)
+ timekeeper.inc_and_update(first_sch_ts_start + i * ONE_TS_BURST_LEN);
+
+ if (fracts)
+ timekeeper.inc_both();
+ // timekeeper.inc_and_update(first_sch_ts_start + 1 * ONE_TS_BURST_LEN);
+
+ timekeeper.dec_by_one(); // oops, off by one?
+
+ timekeeper.set(timekeeper.gsmtime(), rcd->get_first_ts() - ONE_TS_BURST_LEN + to_skip);
+
+ DBGLG() << "this ts: " << rcd->get_first_ts() << " diff full TN: " << fullts << " frac TN: " << fracts
+ << " GSM now: " << timekeeper.gsmtime().FN() << ":" << timekeeper.gsmtime().TN() << " is sch? "
+ << gsm_sch_check_fn(timekeeper.gsmtime().FN()) << std::endl;
+ first_call = false;
+ }
+
+ if (partial_rdofs) {
+ auto first_remaining = ONE_TS_BURST_LEN - partial_rdofs;
+ // memcpy(burst_copy_buffer, partial_buf, partial_rdofs * sizeof(blade_sample_type));
+ auto rd = rcd->read_n(burst_copy_buffer + partial_rdofs, 0, first_remaining);
+ if (rd != first_remaining) {
+ partial_rdofs += rd;
+ return;
+ }
+
+ timekeeper.inc_and_update_safe(rcd->get_first_ts() - partial_rdofs);
+ handle_sch_or_nb();
+ to_skip = first_remaining;
+ }
+
+ // apply sample rate slippage compensation
+ to_skip -= temp_ts_corr_offset;
+
+ // FIXME: happens rarely, read_n start -1 blows up
+ // this is fine: will just be corrected one buffer later
+ if (to_skip < 0)
+ to_skip = 0;
+ else
+ temp_ts_corr_offset = 0;
+
+ const auto left_after_burst = rcd->actual_samples_per_buffer() - to_skip;
+
+ const int full = left_after_burst / ONE_TS_BURST_LEN;
+ const int frac = left_after_burst % ONE_TS_BURST_LEN;
+
+ for (int i = 0; i < full; i++) {
+ rcd->read_n(burst_copy_buffer, to_skip + i * ONE_TS_BURST_LEN, ONE_TS_BURST_LEN);
+ timekeeper.inc_and_update_safe(rcd->get_first_ts() + to_skip + i * ONE_TS_BURST_LEN);
+ handle_sch_or_nb();
+ }
+
+ if (frac)
+ rcd->read_n(burst_copy_buffer, to_skip + full * ONE_TS_BURST_LEN, frac);
+ partial_rdofs = frac;
+}
diff --git a/Transceiver52M/ms/ms_rx_upper.cpp b/Transceiver52M/ms/ms_rx_upper.cpp
new file mode 100644
index 0000000..b87986e
--- /dev/null
+++ b/Transceiver52M/ms/ms_rx_upper.cpp
@@ -0,0 +1,364 @@
+/*
+ * (C) 2022 by sysmocom s.f.m.c. GmbH <info@sysmocom.de>
+ * All Rights Reserved
+ *
+ * Author: Eric Wild <ewild@sysmocom.de>
+ *
+ * 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/>.
+ *
+ */
+
+#include "sigProcLib.h"
+#include "syncthing.h"
+#include "l1if.h"
+#include <signalVector.h>
+#include <radioVector.h>
+#include <radioInterface.h>
+#include "grgsm_vitac/grgsm_vitac.h"
+#include "ms_state.h"
+#include "ms_rx_upper.h"
+
+extern "C" {
+#include "sch.h"
+#include "convolve.h"
+#include "convert.h"
+#include "proto_trxd.h"
+}
+
+#ifdef LOG
+#undef LOG
+#define LOG(...) upper_trx::dummy_log()
+#endif
+
+void upper_trx::start_threads()
+{
+ thr_rx = std::thread([this] {
+ set_name_aff_sched("upper_rx", 1, SCHED_FIFO, sched_get_priority_max(SCHED_FIFO) - 5);
+ while (1) {
+ driveReceiveFIFO();
+ pthread_testcancel();
+ }
+ });
+ msleep(1);
+
+ thr_control = std::thread([this] {
+ set_name_aff_sched("upper_ctrl", 1, SCHED_RR, sched_get_priority_max(SCHED_RR));
+ while (1) {
+ driveControl();
+ pthread_testcancel();
+ }
+ });
+ msleep(1);
+ thr_tx = std::thread([this] {
+ set_name_aff_sched("upper_tx", 1, SCHED_FIFO, sched_get_priority_max(SCHED_FIFO) - 1);
+
+ while (1) {
+ driveTx();
+ pthread_testcancel();
+ }
+ });
+}
+
+void upper_trx::start_ms()
+{
+ ms_trx::start();
+}
+
+/* Detect SCH synchronization sequence within a burst */
+bool upper_trx::detectSCH(ms_TransceiverState *state, signalVector &burst, struct estim_burst_params *ebp)
+{
+ int shift;
+ sch_detect_type full;
+ float mag, threshold = 4.0;
+
+ full = (state->mode == trx_mode::TRX_MODE_MS_TRACK) ? sch_detect_type::SCH_DETECT_NARROW :
+ sch_detect_type::SCH_DETECT_FULL;
+
+ if (!detectSCHBurst(burst, threshold, rx_sps, full, ebp))
+ return false;
+
+ std::clog << "SCH : Timing offset " << ebp->toa << " symbols" << std::endl;
+
+ mag = fabsf(ebp->toa);
+ if (mag < 1.0f)
+ return true;
+
+ shift = (int)(mag / 2.0f);
+ if (!shift)
+ shift++;
+
+ shift = ebp->toa > 0 ? shift : -shift;
+ std::clog << "SCH : shift -> " << shift << " symbols" << std::endl;
+ // mRadioInterface->applyOffset(shift);
+ return false;
+}
+
+SoftVector *upper_trx::pullRadioVector(GSM::Time &wTime, int &RSSI, int &timingOffset) __attribute__((optnone))
+{
+ float pow, avg = 1.0;
+ signalVector *burst;
+ SoftVector *bits = new SoftVector(148);
+ GSM::Time burst_time;
+
+ one_burst e;
+ unsigned char outbin[148];
+ std::complex<float> chan_imp_resp[CHAN_IMP_RESP_LENGTH * d_OSR];
+ std::stringstream dbgout;
+
+ while (!rxqueue.spsc_pop(&e)) {
+ rxqueue.spsc_prep_pop();
+ }
+
+ auto sv = signalVector(625, 40);
+ burst = &sv;
+ auto ss = reinterpret_cast<std::complex<float> *>(burst->begin());
+
+ convert_and_scale<float, int16_t>(burst->begin(), e.burst, ONE_TS_BURST_LEN * 2, 1.f / 2047.f);
+
+ /* Set time and determine correlation type */
+ burst_time = e.gsmts;
+
+ wTime = burst_time;
+
+ CorrType type = mStates.expectedCorrType(burst_time, mRxSlotMask);
+
+ switch (mStates.mode) {
+ case trx_mode::TRX_MODE_MS_TRACK:
+ if (gsm_sch_check_fn(burst_time.FN()) && burst_time.TN() == 0)
+ type = SCH;
+ else if (burst_time.TN() == 0 && !gsm_fcch_check_fn(burst_time.FN())) // all ts0, but not fcch or sch..
+ type = TSC;
+ else if (type == OFF)
+ goto release;
+ break;
+
+ case trx_mode::TRX_MODE_OFF:
+ default:
+ goto release;
+ }
+
+ pow = energyDetect(*burst, 20 * rx_sps);
+ if (pow < -1) {
+ LOG(ALERT) << "Received empty burst";
+ goto release;
+ }
+
+ avg = sqrt(pow);
+
+ if (type == SCH) {
+ int d_c0_burst_start = get_sch_chan_imp_resp(ss, &chan_imp_resp[0]);
+ detect_burst(ss, &chan_imp_resp[0], d_c0_burst_start, outbin);
+
+ for (int i = 0; i < 148; i++)
+ (*bits)[i] = (!outbin[i]) < 1 ? -1 : 1;
+
+ // auto rv = decode_sch(bits->begin(), false);
+ // dbgout << "U SCH@"
+ // << " " << e.gsmts.FN() << ":" << e.gsmts.TN() << " " << d_c0_burst_start
+ // << " DECODE:" << (rv ? "yes" : "---") << std::endl;
+
+ // std::cerr << dbgout.str();
+ } else {
+ float ncmax, dcmax;
+ std::complex<float> chan_imp_resp2[CHAN_IMP_RESP_LENGTH * d_OSR];
+ auto normal_burst_start = get_norm_chan_imp_resp(ss, &chan_imp_resp[0], &ncmax, mTSC);
+ auto dummy_burst_start = get_norm_chan_imp_resp(ss, &chan_imp_resp2[0], &dcmax, TS_DUMMY);
+ auto is_nb = ncmax > dcmax;
+
+ // std::cerr << " U " << (is_nb ? "NB" : "DB") << "@ o nb: " << normal_burst_start
+ // << " o db: " << dummy_burst_start << std::endl;
+
+ if (is_nb)
+ detect_burst(ss, &chan_imp_resp[0], normal_burst_start, outbin);
+ else
+ detect_burst(ss, &chan_imp_resp2[0], dummy_burst_start, outbin);
+
+ for (int i = 0; i < 148; i++)
+ (*bits)[i] = (outbin[i]) < 1 ? -1 : 1;
+ }
+
+ RSSI = (int)floor(20.0 * log10(rxFullScale / avg));
+ timingOffset = (int)round(0);
+
+ return bits;
+
+release:
+
+ delete bits;
+ return NULL;
+}
+
+void upper_trx::driveReceiveFIFO()
+{
+ SoftVector *rxBurst = NULL;
+ int RSSI;
+ int TOA; // in 1/256 of a symbol
+ GSM::Time burstTime;
+
+ rxBurst = pullRadioVector(burstTime, RSSI, TOA);
+ if (!mOn)
+ return;
+
+ // _only_ return useless fcch trash to tickle trxcons tx path
+ // auto is_fcch = [&burstTime]{ return burstTime.TN() == 0 && gsm_fcch_check_fn(burstTime.FN());};
+ // if(!rxBurst && !is_fcch())
+ // return;
+
+ auto response = (trxd_from_trx *)calloc(1, sizeof(trxd_from_trx));
+
+ response->ts = burstTime.TN();
+ response->fn = htonl(burstTime.FN());
+ response->rssi = RSSI;
+ response->toa = htons(TOA);
+ if (rxBurst) {
+ SoftVector::const_iterator burstItr = rxBurst->begin();
+ if (gsm_sch_check_fn(burstTime.FN())) {
+ clamp_array(rxBurst->begin(), 148, 1.5f);
+ for (unsigned int i = 0; i < gSlotLen; i++) {
+ auto val = *burstItr++;
+ auto vval = isnan(val) ? 0 : val;
+ ((int8_t *)response->symbols)[i] = round((vval - 0.5) * 64.0);
+ }
+ } else {
+ // invert and fix to +-127 sbits
+ for (int i = 0; i < 148; i++)
+ ((int8_t *)response->symbols)[i] = *burstItr++ > 0.0f ? -127 : 127;
+ }
+
+ delete rxBurst;
+ }
+
+#ifdef IPCIF
+ push_d(response);
+#else
+ int rv = sendto(mDataSockets, response, sizeof(trxd_from_trx), 0, (struct sockaddr *)&datadest,
+ sizeof(struct sockaddr_in));
+ if (rv < 0) {
+ std::cerr << "fuck, send?" << std::endl;
+ exit(0);
+ }
+ free(response);
+
+#endif
+}
+
+void upper_trx::driveTx()
+{
+#ifdef IPCIF
+ auto burst = pop_d();
+ if (!burst) {
+ // std::cerr << "wtf no tx burst?" << std::endl;
+ // exit(0);
+ continue;
+ }
+#else
+ trxd_to_trx buffer;
+
+ socklen_t addr_len = sizeof(datasrc);
+ int rdln = recvfrom(mDataSockets, (void *)&buffer, sizeof(trxd_to_trx), 0, &datasrc, &addr_len);
+ if (rdln < 0 && errno == EAGAIN) {
+ std::cerr << "fuck, rcv?" << std::endl;
+ exit(0);
+ }
+
+ trxd_to_trx *burst = &buffer;
+#endif
+ auto proper_fn = ntohl(burst->fn);
+ // std::cerr << "got burst!" << proper_fn << ":" << burst->ts
+ // << " current: " << timekeeper.gsmtime().FN()
+ // << " dff: " << (int64_t)((int64_t)timekeeper.gsmtime().FN() - (int64_t)proper_fn)
+ // << std::endl;
+
+ auto currTime = GSM::Time(proper_fn, burst->ts);
+ int RSSI = (int)burst->txlev;
+
+ static BitVector newBurst(gSlotLen);
+ BitVector::iterator itr = newBurst.begin();
+ auto *bufferItr = burst->symbols;
+ while (itr < newBurst.end())
+ *itr++ = *bufferItr++;
+
+ auto txburst = modulateBurst(newBurst, 8 + (currTime.TN() % 4 == 0), 4);
+ scaleVector(*txburst, txFullScale * 0.7 /* * pow(10, -RSSI / 10)*/);
+
+ // float -> int16
+ blade_sample_type burst_buf[txburst->size()];
+ convert_and_scale<int16_t, float>(burst_buf, txburst->begin(), txburst->size() * 2, 1);
+
+ // auto check = signalVector(txburst->size(), 40);
+ // convert_and_scale<float, int16_t, 1>(check.begin(), burst_buf, txburst->size() * 2);
+ // estim_burst_params ebp;
+ // auto d = detectAnyBurst(check, 2, 4, 4, CorrType::RACH, 40, &ebp);
+ // if(d)
+ // std::cerr << "RACH D! " << ebp.toa << std::endl;
+ // else
+ // std::cerr << "RACH NOOOOOOOOOO D! " << ebp.toa << std::endl;
+
+ // memory read --binary --outfile /tmp/mem.bin &burst_buf[0] --count 2500 --force
+
+ submit_burst(burst_buf, txburst->size(), currTime);
+
+#ifdef IPCIF
+ free(burst);
+#endif
+}
+
+// __attribute__((xray_always_instrument)) static void *rx_stream_callback(struct bladerf *dev,
+// struct bladerf_stream *stream,
+// struct bladerf_metadata *meta, void *samples,
+// size_t num_samples, void *user_data)
+// {
+// struct ms_trx *trx = (struct ms_trx *)user_data;
+// return trx->rx_cb(dev, stream, meta, samples, num_samples, user_data);
+// }
+
+// __attribute__((xray_always_instrument)) static void *tx_stream_callback(struct bladerf *dev,
+// struct bladerf_stream *stream,
+// struct bladerf_metadata *meta, void *samples,
+// size_t num_samples, void *user_data)
+// {
+// struct ms_trx *trx = (struct ms_trx *)user_data;
+// return BLADERF_STREAM_NO_DATA;
+// }
+
+int trxc_main(int argc, char *argv[])
+{
+ pthread_setname_np(pthread_self(), "main_trxc");
+
+ convolve_init();
+ convert_init();
+ sigProcLibSetup();
+ initvita();
+
+ int status = 0;
+ auto trx = new upper_trx();
+ trx->do_auto_gain = true;
+
+ status = trx->init_dev_and_streams(0, 0);
+ trx->start_threads();
+
+ return status;
+}
+
+extern "C" volatile bool gshutdown = false;
+extern "C" void init_external_transceiver(int argc, char **argv)
+{
+ std::cout << "init?" << std::endl;
+ trxc_main(argc, argv);
+}
+
+extern "C" void stop_trx()
+{
+ std::cout << "Shutting down transceiver..." << std::endl;
+}
diff --git a/Transceiver52M/ms/ms_rx_upper.h b/Transceiver52M/ms/ms_rx_upper.h
new file mode 100644
index 0000000..09154bf
--- /dev/null
+++ b/Transceiver52M/ms/ms_rx_upper.h
@@ -0,0 +1,121 @@
+
+#pragma once
+
+/*
+ * (C) 2022 by sysmocom s.f.m.c. GmbH <info@sysmocom.de>
+ * All Rights Reserved
+ *
+ * Author: Eric Wild <ewild@sysmocom.de>
+ *
+ * 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/>.
+ *
+ */
+#include <netdb.h>
+#include <sys/socket.h>
+#include <arpa/inet.h>
+
+#include "GSMCommon.h"
+#include "radioClock.h"
+#include "syncthing.h"
+#include "ms_state.h"
+
+class upper_trx : public ms_trx {
+ int rx_sps, tx_sps;
+
+ ms_TransceiverState mStates;
+
+ bool mOn; ///< flag to indicate that transceiver is powered on
+ double mTxFreq; ///< the transmit frequency
+ double mRxFreq; ///< the receive frequency
+ int mPower; ///< the transmit power in dB
+ unsigned mMaxExpectedDelay; ///< maximum TOA offset in GSM symbols
+ unsigned long long mRxSlotMask[8]; ///< MS - enabled multiframe slot mask
+
+ int mDataSockets;
+ sockaddr_in datadest;
+ sockaddr datasrc;
+ int mCtrlSockets;
+ sockaddr_in ctrldest;
+ sockaddr ctrlsrc;
+
+ void openudp(int *mSocketFD, unsigned short localPort, const char *wlocalIP)
+ {
+ *mSocketFD = socket(AF_INET, SOCK_DGRAM, 0);
+ int on = 1;
+ setsockopt(*mSocketFD, SOL_SOCKET, SO_REUSEADDR, &on, sizeof(on));
+
+ struct sockaddr_in address;
+ size_t length = sizeof(address);
+ bzero(&address, length);
+ address.sin_family = AF_INET;
+ address.sin_addr.s_addr = inet_addr(wlocalIP);
+ address.sin_port = htons(localPort);
+ if (bind(*mSocketFD, (struct sockaddr *)&address, length) < 0) {
+ std::cerr << "bind fail!" << std::endl;
+ exit(0);
+ }
+ }
+
+ bool resolveAddress(struct sockaddr_in *address, const char *host, unsigned short port)
+ {
+ struct hostent *hp;
+ int h_errno_local;
+
+ struct hostent hostData;
+ char tmpBuffer[2048];
+
+ auto rc = gethostbyname2_r(host, AF_INET, &hostData, tmpBuffer, sizeof(tmpBuffer), &hp, &h_errno_local);
+ if (hp == NULL || hp->h_addrtype != AF_INET || rc != 0) {
+ std::cerr << "WARNING -- gethostbyname() failed for " << host << ", "
+ << hstrerror(h_errno_local);
+ exit(0);
+ return false;
+ }
+
+ address->sin_family = hp->h_addrtype;
+ assert(sizeof(address->sin_addr) == hp->h_length);
+ memcpy(&(address->sin_addr), hp->h_addr_list[0], hp->h_length);
+ address->sin_port = htons(port);
+ return true;
+ }
+
+ void driveControl();
+ void driveReceiveFIFO();
+ void driveTx();
+ void commandhandler(char *buffer, char *response);
+ void writeClockInterface(){};
+
+ SoftVector *pullRadioVector(GSM::Time &wTime, int &RSSI, int &timingOffset);
+
+ bool detectSCH(ms_TransceiverState *state, signalVector &burst, struct estim_burst_params *ebp);
+
+ std::thread thr_control, thr_rx, thr_tx;
+
+ public:
+ void start_threads();
+ void start_ms();
+
+ upper_trx() : rx_sps(4), tx_sps(4)
+ {
+ auto c_srcport = 6700 + 2 * 0 + 1;
+ auto c_dstport = 6700 + 2 * 0 + 101;
+ auto d_srcport = 6700 + 2 * 0 + 2;
+ auto d_dstport = 6700 + 2 * 0 + 102;
+
+ openudp(&mCtrlSockets, c_srcport, "127.0.0.1");
+ openudp(&mDataSockets, d_srcport, "127.0.0.1");
+ resolveAddress(&ctrldest, "127.0.0.1", c_dstport);
+ resolveAddress(&datadest, "127.0.0.1", d_dstport);
+ };
+};
diff --git a/Transceiver52M/ms/ms_state.h b/Transceiver52M/ms/ms_state.h
new file mode 100644
index 0000000..c00d072
--- /dev/null
+++ b/Transceiver52M/ms/ms_state.h
@@ -0,0 +1,175 @@
+#pragma once
+
+#include <radioVector.h>
+#include <signalVector.h>
+
+enum class trx_mode {
+ TRX_MODE_OFF,
+ TRX_MODE_BTS,
+ TRX_MODE_MS_ACQUIRE,
+ TRX_MODE_MS_TRACK,
+};
+
+enum class ChannelCombination {
+ FILL, ///< Channel is transmitted, but unused
+ I, ///< TCH/FS
+ II, ///< TCH/HS, idle every other slot
+ III, ///< TCH/HS
+ IV, ///< FCCH+SCH+CCCH+BCCH, uplink RACH
+ V, ///< FCCH+SCH+CCCH+BCCH+SDCCH/4+SACCH/4, uplink RACH+SDCCH/4
+ VI, ///< CCCH+BCCH, uplink RACH
+ VII, ///< SDCCH/8 + SACCH/8
+ VIII, ///< TCH/F + FACCH/F + SACCH/M
+ IX, ///< TCH/F + SACCH/M
+ X, ///< TCH/FD + SACCH/MD
+ XI, ///< PBCCH+PCCCH+PDTCH+PACCH+PTCCH
+ XII, ///< PCCCH+PDTCH+PACCH+PTCCH
+ XIII, ///< PDTCH+PACCH+PTCCH
+ NONE_INACTIVE, ///< Channel is inactive, default
+ LOOPBACK ///< similar go VII, used in loopback testing
+};
+
+struct ms_TransceiverState {
+ ms_TransceiverState() : mFreqOffsets(10), mode(trx_mode::TRX_MODE_OFF)
+ {
+ for (int i = 0; i < 8; i++) {
+ chanType[i] = ChannelCombination::NONE_INACTIVE;
+ fillerModulus[i] = 26;
+
+ for (int n = 0; n < 102; n++)
+ fillerTable[n][i] = nullptr;
+ }
+ }
+
+ ~ms_TransceiverState()
+ {
+ for (int i = 0; i < 8; i++) {
+ for (int n = 0; n < 102; n++)
+ delete fillerTable[n][i];
+ }
+ }
+
+ void setModulus(size_t timeslot)
+ {
+ switch (chanType[timeslot]) {
+ case ChannelCombination::NONE_INACTIVE:
+ case ChannelCombination::I:
+ case ChannelCombination::II:
+ case ChannelCombination::III:
+ case ChannelCombination::FILL:
+ fillerModulus[timeslot] = 26;
+ break;
+ case ChannelCombination::IV:
+ case ChannelCombination::VI:
+ case ChannelCombination::V:
+ fillerModulus[timeslot] = 51;
+ break;
+ //case V:
+ case ChannelCombination::VII:
+ fillerModulus[timeslot] = 102;
+ break;
+ case ChannelCombination::XIII:
+ fillerModulus[timeslot] = 52;
+ break;
+ default:
+ break;
+ }
+ }
+
+ CorrType expectedCorrType(GSM::Time currTime, unsigned long long *mRxSlotMask)
+ {
+ unsigned burstTN = currTime.TN();
+ unsigned burstFN = currTime.FN();
+
+ if (mode == trx_mode::TRX_MODE_MS_TRACK) {
+ /* 102 modulus case currently unhandled */
+ if (fillerModulus[burstTN] > 52)
+ return OFF;
+
+ int modFN = burstFN % fillerModulus[burstTN];
+ unsigned long long reg = (unsigned long long)1 << modFN;
+ if (reg & mRxSlotMask[burstTN])
+ return TSC;
+ else
+ return OFF;
+ }
+
+ switch (chanType[burstTN]) {
+ case ChannelCombination::NONE_INACTIVE:
+ return OFF;
+ break;
+ case ChannelCombination::FILL:
+ return IDLE;
+ break;
+ case ChannelCombination::I:
+ return TSC;
+ /*if (burstFN % 26 == 25)
+ return IDLE;
+ else
+ return TSC;*/
+ break;
+ case ChannelCombination::II:
+ return TSC;
+ break;
+ case ChannelCombination::III:
+ return TSC;
+ break;
+ case ChannelCombination::IV:
+ case ChannelCombination::VI:
+ return RACH;
+ break;
+ case ChannelCombination::V: {
+ int mod51 = burstFN % 51;
+ if ((mod51 <= 36) && (mod51 >= 14))
+ return RACH;
+ else if ((mod51 == 4) || (mod51 == 5))
+ return RACH;
+ else if ((mod51 == 45) || (mod51 == 46))
+ return RACH;
+ else
+ return TSC;
+ break;
+ }
+ case ChannelCombination::VII:
+ if ((burstFN % 51 <= 14) && (burstFN % 51 >= 12))
+ return IDLE;
+ else
+ return TSC;
+ break;
+ case ChannelCombination::XIII: {
+ int mod52 = burstFN % 52;
+ if ((mod52 == 12) || (mod52 == 38))
+ return RACH;
+ else if ((mod52 == 25) || (mod52 == 51))
+ return IDLE;
+ else
+ return TSC;
+ break;
+ }
+ case ChannelCombination::LOOPBACK:
+ if ((burstFN % 51 <= 50) && (burstFN % 51 >= 48))
+ return IDLE;
+ else
+ return TSC;
+ break;
+ default:
+ return OFF;
+ break;
+ }
+ }
+
+ /* Initialize a multiframe slot in the filler table */
+ void init(size_t slot, signalVector *burst, bool fill);
+
+ ChannelCombination chanType[8];
+
+ /* The filler table */
+ signalVector *fillerTable[102][8];
+ int fillerModulus[8];
+
+ /* Received noise energy levels */
+ avgVector mFreqOffsets;
+
+ /* Transceiver mode */
+ trx_mode mode;
+}; \ No newline at end of file
diff --git a/Transceiver52M/ms/syncthing.cpp b/Transceiver52M/ms/syncthing.cpp
new file mode 100644
index 0000000..4f58c39
--- /dev/null
+++ b/Transceiver52M/ms/syncthing.cpp
@@ -0,0 +1,332 @@
+
+/*
+ * (C) 2022 by sysmocom s.f.m.c. GmbH <info@sysmocom.de>
+ * All Rights Reserved
+ *
+ * Author: Eric Wild <ewild@sysmocom.de>
+ *
+ * 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/>.
+ *
+ */
+#include "GSMCommon.h"
+#include <atomic>
+#include <cassert>
+#include <complex>
+#include <iostream>
+#include <cstdlib>
+#include <cstdio>
+#include <thread>
+#include <fstream>
+
+#include "sigProcLib.h"
+
+#include "syncthing.h"
+#include "ms_rx_burst.h"
+#include "grgsm_vitac/grgsm_vitac.h"
+
+extern "C" {
+#include "sch.h"
+#include "convolve.h"
+#include "convert.h"
+}
+
+dummylog ms_trx::dummy_log;
+
+const int offset_start = -15;
+int offsetrange = 200;
+static int offset_ctr = 0;
+
+void tx_test(ms_trx *t, ts_hitter_q_t *q, unsigned int *tsc)
+{
+ sched_param sch_params;
+ sch_params.sched_priority = sched_get_priority_max(SCHED_FIFO);
+ pthread_setschedparam(pthread_self(), SCHED_FIFO, &sch_params);
+
+ auto burst = genRandAccessBurst(0, 4, 0);
+ scaleVector(*burst, t->txFullScale * 0.7);
+
+ // float -> int16
+ blade_sample_type burst_buf[burst->size()];
+ convert_and_scale<int16_t, float>(burst_buf, burst->begin(), burst->size() * 2, 1);
+
+ while (1) {
+ GSM::Time target;
+ while (!q->spsc_pop(&target)) {
+ q->spsc_prep_pop();
+ }
+
+ std::cerr << std::endl << "\x1B[32m hitting " << target.FN() << "\033[0m" << std::endl;
+
+ int timing_advance = 0;
+ int64_t now_ts;
+ GSM::Time now_time;
+ target.incTN(3); // ul dl offset
+ int target_fn = target.FN();
+ int target_tn = target.TN();
+ t->timekeeper.get_both(&now_time, &now_ts);
+
+ auto diff_fn = GSM::FNDelta(target_fn, now_time.FN());
+ int diff_tn = (target_tn - (int)now_time.TN()) % 8;
+ auto tosend = GSM::Time(diff_fn, 0);
+
+ if (diff_tn > 0)
+ tosend.incTN(diff_tn);
+ else if (diff_tn < 0)
+ tosend.decTN(-diff_tn);
+
+ // in thory fn equal and tn+3 equal is also a problem...
+ if (diff_fn < 0 || (diff_fn == 0 && (now_time.TN() - target_tn < 1))) {
+ std::cerr << "## TX too late?! fn DIFF:" << diff_fn << " tn LOCAL: " << now_time.TN()
+ << " tn OTHER: " << target_tn << std::endl;
+ return;
+ }
+
+ auto check = now_time + tosend;
+ int64_t send_ts =
+ now_ts + tosend.FN() * 8 * ONE_TS_BURST_LEN + tosend.TN() * ONE_TS_BURST_LEN - timing_advance;
+
+ // std::cerr << "## fn DIFF: " << diff_fn << " ## tn DIFF: " << diff_tn
+ // << " tn LOCAL: " << now_time.TN() << " tn OTHER: " << target_tn
+ // << " tndiff" << diff_tn << " tosend:" << tosend.FN() << ":" << tosend.TN()
+ // << " calc: " << check.FN() << ":" <<check.TN()
+ // << " target: " << target.FN() << ":" <<target.TN()
+ // << " ts now: " << now_ts << " target ts:" << send_ts << std::endl;
+
+ unsigned int pad = 4 * 25;
+ blade_sample_type buf2[burst->size() + pad];
+ memset(buf2, 0, pad * sizeof(blade_sample_type));
+ memcpy(&buf2[pad], burst_buf, burst->size() * sizeof(blade_sample_type));
+
+ assert(target.FN() == check.FN());
+ assert(target.TN() == check.TN());
+ assert(target.FN() % 51 == 21);
+
+ // auto this_offset = offset_start + (offset_ctr++ % offsetrange);
+ // std::cerr << "-- O " << this_offset << std::endl;
+ // send_ts = now_ts + ((target.FN() * 8 + (int)target.TN()) - (now_time.FN() * 8 + (int)now_time.TN())) * ONE_TS_BURST_LEN - timing_advance;
+
+ t->submit_burst_ts(buf2, burst->size() + pad, send_ts - pad);
+
+ // signalVector test(burst->size() + pad);
+ // convert_and_scale<float, int16_t>(test.begin(), buf2, burst->size() * 2 + pad, 1.f / 2047.f);
+ // estim_burst_params ebp;
+ // auto det = detectAnyBurst(test, 0, 4, 4, CorrType::RACH, 40, &ebp);
+ // if (det > 0)
+ // std::cerr << "## Y " << ebp.toa << std::endl;
+ // else
+ // std::cerr << "## NOOOOOOOOO " << ebp.toa << std::endl;
+ }
+}
+#ifdef SYNCTHINGONLY
+template <typename A> auto parsec(std::vector<std::string> &v, A &itr, std::string arg, bool *rv)
+{
+ if (*itr == arg) {
+ *rv = true;
+ return true;
+ }
+ return false;
+}
+
+template <typename A, typename B, typename C>
+bool parsec(std::vector<std::string> &v, A &itr, std::string arg, B f, C *rv)
+{
+ if (*itr == arg) {
+ itr++;
+ if (itr != v.end()) {
+ *rv = f(itr->c_str());
+ return true;
+ }
+ }
+ return false;
+}
+template <typename A> bool parsec(std::vector<std::string> &v, A &itr, std::string arg, int scale, int *rv)
+{
+ return parsec(
+ v, itr, arg, [scale](const char *v) -> auto{ return atoi(v) * scale; }, rv);
+}
+template <typename A> bool parsec(std::vector<std::string> &v, A &itr, std::string arg, int scale, unsigned int *rv)
+{
+ return parsec(
+ v, itr, arg, [scale](const char *v) -> auto{ return atoi(v) * scale; }, rv);
+}
+
+int main(int argc, char *argv[])
+{
+ cpu_set_t cpuset;
+
+ CPU_ZERO(&cpuset);
+ CPU_SET(2, &cpuset);
+
+ auto rv = pthread_setaffinity_np(pthread_self(), sizeof(cpuset), &cpuset);
+ if (rv < 0) {
+ std::cerr << "affinity: errreur! " << std::strerror(errno);
+ return 0;
+ }
+
+ unsigned int default_tx_freq(881000 * 1000), default_rx_freq(926000 * 1000);
+ unsigned int grx = 20, gtx = 20;
+ bool tx_flag = false;
+ pthread_setname_np(pthread_self(), "main");
+ convolve_init();
+ convert_init();
+ sigProcLibSetup();
+ initvita();
+
+ int status = 0;
+ auto trx = new ms_trx();
+ trx->do_auto_gain = true;
+
+ std::vector<std::string> args(argv + 1, argv + argc);
+ for (auto i = args.begin(); i != args.end(); ++i) {
+ parsec(args, i, "-r", 1000, &default_rx_freq);
+ parsec(args, i, "-t", 1000, &default_tx_freq);
+ parsec(args, i, "-gr", 1, &grx);
+ parsec(args, i, "-gt", 1, &gtx);
+ parsec(args, i, "-tx", &tx_flag);
+ }
+
+ std::cerr << "usage: " << argv[0] << " <rxfreq in khz, i.e. 926000> [txfreq in khz, i.e. 881000] [TX]"
+ << std::endl
+ << "rx" << (argc == 1 ? " (default) " : " ") << default_rx_freq << "hz, tx " << default_tx_freq
+ << "hz" << std::endl
+ << "gain rx " << grx << " gain tx " << gtx << std::endl
+ << (tx_flag ? "##!!## RACH TX ACTIVE ##!!##" : "-- no rach tx --") << std::endl;
+
+ status = trx->init_dev_and_streams(0, 0);
+ if (status < 0)
+ return status;
+ trx->tuneRx(default_rx_freq);
+ trx->tuneTx(default_tx_freq);
+ trx->setRxGain(grx);
+ trx->setTxGain(gtx);
+
+ if (status == 0) {
+ // FIXME: hacks! needs exit flag for detached threads!
+
+ std::thread(rcv_bursts_test, &trx->rxqueue, &trx->mTSC).detach();
+ if (tx_flag)
+ std::thread(tx_test, trx, &trx->ts_hitter_q, &trx->mTSC).detach();
+ trx->start();
+ do {
+ sleep(1);
+ } while (1);
+
+ trx->stop_threads();
+ }
+ delete trx;
+
+ return status;
+}
+#endif
+
+int ms_trx::init_streams(void *rx_cb, void *tx_cb)
+{
+ return 0;
+}
+
+int ms_trx::init_dev_and_streams(void *rx_cb, void *tx_cb)
+{
+ int status = 0;
+ status = base::init_device(rx_bh(), tx_bh());
+ if (status < 0) {
+ std::cerr << "failed to init dev!" << std::endl;
+ return -1;
+ }
+ return status;
+}
+
+bh_fn_t ms_trx::rx_bh()
+{
+ return [this](dev_buf_t *rcd) -> int {
+ if (this->search_for_sch(rcd) == SCH_STATE::FOUND)
+ this->grab_bursts(rcd);
+ return 0;
+ };
+}
+
+bh_fn_t ms_trx::tx_bh()
+{
+ return [this](dev_buf_t *rcd) -> int {
+#pragma unused(rcd)
+ auto y = this;
+#pragma unused(y)
+ /* nothing to do here */
+ return 0;
+ };
+}
+
+void ms_trx::start()
+{
+ auto fn = get_rx_burst_handler_fn(rx_bh());
+ rx_task = std::thread(fn);
+
+ usleep(1000);
+ auto fn2 = get_tx_burst_handler_fn(tx_bh());
+ tx_task = std::thread(fn2);
+}
+
+void ms_trx::stop_threads()
+{
+ std::cerr << "killing threads...\r\n" << std::endl;
+ rx_task.join();
+}
+
+void ms_trx::submit_burst(blade_sample_type *buffer, int len, GSM::Time target)
+{
+ int64_t now_ts;
+ GSM::Time now_time;
+ target.incTN(3); // ul dl offset
+ int target_fn = target.FN();
+ int target_tn = target.TN();
+ timekeeper.get_both(&now_time, &now_ts);
+
+ auto diff_fn = GSM::FNDelta(target_fn, now_time.FN());
+ int diff_tn = (target_tn - (int)now_time.TN()) % 8;
+ auto tosend = GSM::Time(diff_fn, 0);
+
+ if (diff_tn > 0)
+ tosend.incTN(diff_tn);
+ else
+ tosend.decTN(-diff_tn);
+
+ // in thory fn equal and tn+3 equal is also a problem...
+ if (diff_fn < 0 || (diff_fn == 0 && (now_time.TN() - target_tn < 1))) {
+ std::cerr << "## TX too late?! fn DIFF:" << diff_fn << " tn LOCAL: " << now_time.TN()
+ << " tn OTHER: " << target_tn << std::endl;
+ return;
+ }
+
+ auto check = now_time + tosend;
+ int64_t send_ts = now_ts + tosend.FN() * 8 * ONE_TS_BURST_LEN + tosend.TN() * ONE_TS_BURST_LEN - timing_advance;
+
+ // std::cerr << "## fn DIFF: " << diff_fn << " ## tn DIFF: " << diff_tn
+ // << " tn LOCAL/OTHER: " << now_time.TN() << "/" << target_tn
+ // << " tndiff" << diff_tn << " tosend:" << tosend.FN() << ":" << tosend.TN()
+ // << " check: " << check.FN() << ":" <<check.TN()
+ // << " target: " << target.FN() << ":" <<target.TN()
+ // << " ts now: " << now_ts << " target ts:" << send_ts << std::endl;
+
+#if 1
+ unsigned int pad = 4 * 4;
+ blade_sample_type buf2[len + pad];
+ memset(buf2, 0, pad * sizeof(blade_sample_type));
+ memcpy(&buf2[pad], buffer, len * sizeof(blade_sample_type));
+
+ assert(target.FN() == check.FN());
+ assert(target.TN() == check.TN());
+ submit_burst_ts(buf2, len + pad, send_ts - pad);
+#else
+ submit_burst_ts(buffer, len, send_ts);
+#endif
+}
diff --git a/Transceiver52M/ms/syncthing.h b/Transceiver52M/ms/syncthing.h
new file mode 100644
index 0000000..8fb4aeb
--- /dev/null
+++ b/Transceiver52M/ms/syncthing.h
@@ -0,0 +1,224 @@
+#pragma once
+
+/*
+ * (C) 2022 by sysmocom s.f.m.c. GmbH <info@sysmocom.de>
+ * All Rights Reserved
+ *
+ * Author: Eric Wild <ewild@sysmocom.de>
+ *
+ * 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/>.
+ *
+ */
+
+#include <atomic>
+#include <cassert>
+#include <complex>
+#include <cstdint>
+#include <mutex>
+#include <iostream>
+#include <thread>
+
+#if defined(BUILDBLADE)
+#include "bladerf_specific.h"
+#define BASET blade_hw<ms_trx>
+#elif defined(BUILDUHD)
+#include "uhd_specific.h"
+#define BASET uhd_hw<ms_trx>
+#else
+#error wat? no device..
+#endif
+
+#include "GSMCommon.h"
+#include "itrq.h"
+
+const unsigned int ONE_TS_BURST_LEN = (3 + 58 + 26 + 58 + 3 + 8.25) * 4 /*sps*/;
+const unsigned int NUM_RXQ_FRAMES = 12 * 1; // rx thread <-> upper rx queue
+const unsigned int SCH_LEN_SPS = (ONE_TS_BURST_LEN * 8 /*ts*/ * 12 /*frames*/);
+
+template <typename T> void clamp_array(T *start2, unsigned int len, T max)
+{
+ for (int i = 0; i < len; i++) {
+ const T t1 = start2[i] < -max ? -max : start2[i];
+ const T t2 = t1 > max ? max : t1;
+ start2[i] = t2;
+ }
+}
+template <typename DST_T, typename SRC_T, typename ST>
+void convert_and_scale(void *dst, void *src, unsigned int src_len, ST scale)
+{
+ for (unsigned int i = 0; i < src_len; i++)
+ reinterpret_cast<DST_T *>(dst)[i] = static_cast<DST_T>((reinterpret_cast<SRC_T *>(src)[i])) * scale;
+}
+template <typename DST_T, typename SRC_T> void convert_and_scale_default(void *dst, void *src, unsigned int src_len)
+{
+ return convert_and_scale<DST_T, SRC_T>(dst, src, src_len, SAMPLE_SCALE_FACTOR);
+}
+
+struct one_burst {
+ GSM::Time gsmts;
+ blade_sample_type burst[ONE_TS_BURST_LEN];
+};
+
+using rx_queue_t = spsc_cond<8 * NUM_RXQ_FRAMES, one_burst, true, false>;
+
+enum class SCH_STATE { SEARCHING, FOUND };
+
+class dummylog : private std::streambuf {
+ std::ostream null_stream;
+
+ public:
+ dummylog() : null_stream(this){};
+ ~dummylog() override{};
+ std::ostream &operator()()
+ {
+ return null_stream;
+ }
+ int overflow(int c) override
+ {
+ return c;
+ }
+};
+
+// keeps relationship between gsm time and (continuously adjusted) ts
+class time_keeper {
+ GSM::Time global_time_keeper;
+ int64_t global_ts_keeper;
+ std::mutex m;
+
+ public:
+ time_keeper() : global_time_keeper(0), global_ts_keeper(0)
+ {
+ }
+
+ void set(GSM::Time t, int64_t ts)
+ {
+ std::lock_guard<std::mutex> g(m);
+ global_time_keeper = t;
+ global_ts_keeper = ts;
+ }
+ void inc_both()
+ {
+ std::lock_guard<std::mutex> g(m);
+ global_time_keeper.incTN(1);
+ global_ts_keeper += ONE_TS_BURST_LEN;
+ }
+ void inc_and_update(int64_t new_ts)
+ {
+ std::lock_guard<std::mutex> g(m);
+ global_time_keeper.incTN(1);
+ global_ts_keeper = new_ts;
+ // std::cerr << "u " << new_ts << std::endl;
+ }
+ void inc_and_update_safe(int64_t new_ts)
+ {
+ std::lock_guard<std::mutex> g(m);
+ auto diff = new_ts - global_ts_keeper;
+ assert(diff < 1.5 * ONE_TS_BURST_LEN);
+ assert(diff > 0.5 * ONE_TS_BURST_LEN);
+ global_time_keeper.incTN(1);
+ global_ts_keeper = new_ts;
+ // std::cerr << "s " << new_ts << std::endl;
+ }
+ void dec_by_one()
+ {
+ std::lock_guard<std::mutex> g(m);
+ global_time_keeper.decTN(1);
+ global_ts_keeper -= ONE_TS_BURST_LEN;
+ }
+ auto get_ts()
+ {
+ std::lock_guard<std::mutex> g(m);
+ return global_ts_keeper;
+ }
+ auto gsmtime()
+ {
+ std::lock_guard<std::mutex> g(m);
+ return global_time_keeper;
+ }
+ void get_both(GSM::Time *t, int64_t *ts)
+ {
+ std::lock_guard<std::mutex> g(m);
+ *t = global_time_keeper;
+ *ts = global_ts_keeper;
+ }
+};
+
+using ts_hitter_q_t = spsc_cond<64, GSM::Time, true, false>;
+
+struct ms_trx : public BASET {
+ using base = BASET;
+ static dummylog dummy_log;
+ unsigned int mTSC;
+ unsigned int mBSIC;
+ int timing_advance;
+ bool do_auto_gain;
+
+ std::thread rx_task;
+ std::thread tx_task;
+ std::thread *calcrval_task;
+
+ // provides bursts to upper rx thread
+ rx_queue_t rxqueue;
+#ifdef SYNCTHINGONLY
+ ts_hitter_q_t ts_hitter_q;
+#endif
+ blade_sample_type *first_sch_buf;
+ blade_sample_type *burst_copy_buffer;
+
+ uint64_t first_sch_buf_rcv_ts;
+ std::atomic<bool> rcv_done;
+ std::atomic<bool> sch_thread_done;
+
+ int64_t temp_ts_corr_offset = 0;
+ int64_t first_sch_ts_start = -1;
+
+ time_keeper timekeeper;
+
+ void start();
+
+ bool handle_sch_or_nb(bool first = false);
+ bool handle_sch(bool first = false);
+ bool decode_sch(float *bits, bool update_global_clock);
+ SCH_STATE search_for_sch(dev_buf_t *rcd);
+ void grab_bursts(dev_buf_t *rcd);
+
+ int init_device();
+ int init_streams(void *rx_cb, void *tx_cb);
+ int init_dev_and_streams(void *rx_cb, void *tx_cb);
+ void stop_threads();
+ void *rx_cb(ms_trx *t);
+ void *tx_cb();
+ void maybe_update_gain(one_burst &brst);
+
+ ms_trx()
+ : timing_advance(0), do_auto_gain(false), rxqueue(), first_sch_buf(new blade_sample_type[SCH_LEN_SPS]),
+ burst_copy_buffer(new blade_sample_type[ONE_TS_BURST_LEN]), rcv_done{ false }, sch_thread_done{ false }
+ {
+ }
+
+ virtual ~ms_trx()
+ {
+ delete[] burst_copy_buffer;
+ delete[] first_sch_buf;
+ }
+ bh_fn_t rx_bh();
+ bh_fn_t tx_bh();
+
+ void submit_burst(blade_sample_type *buffer, int len, GSM::Time);
+ void set_ta(int val)
+ {
+ assert(val > -127 && val < 128);
+ timing_advance = val * 4;
+ }
+};
diff --git a/Transceiver52M/ms/uhd_specific.h b/Transceiver52M/ms/uhd_specific.h
new file mode 100644
index 0000000..88b9a1b
--- /dev/null
+++ b/Transceiver52M/ms/uhd_specific.h
@@ -0,0 +1,274 @@
+#pragma once
+
+/*
+ * (C) 2022 by sysmocom s.f.m.c. GmbH <info@sysmocom.de>
+ * All Rights Reserved
+ *
+ * Author: Eric Wild <ewild@sysmocom.de>
+ *
+ * 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/>.
+ *
+ */
+
+#include <uhd/version.hpp>
+#include <uhd/usrp/multi_usrp.hpp>
+#include <uhd/types/metadata.hpp>
+#include <complex>
+#include <cstring>
+#include <iostream>
+#include <thread>
+
+#include <Timeval.h>
+#include <vector>
+
+using blade_sample_type = std::complex<int16_t>;
+const int SAMPLE_SCALE_FACTOR = 1;
+
+struct uhd_buf_wrap {
+ double rxticks;
+ size_t num_samps;
+ uhd::rx_metadata_t *md;
+ blade_sample_type *buf;
+ auto actual_samples_per_buffer()
+ {
+ return num_samps;
+ }
+ long get_first_ts()
+ {
+ return md->time_spec.to_ticks(rxticks);
+ }
+ int readall(blade_sample_type *outaddr)
+ {
+ memcpy(outaddr, buf, num_samps * sizeof(blade_sample_type));
+ return num_samps;
+ }
+ int read_n(blade_sample_type *outaddr, int start, int num)
+ {
+ assert(start >= 0);
+ auto to_read = std::min((int)num_samps - start, num);
+ assert(to_read >= 0);
+ memcpy(outaddr, buf + start, to_read * sizeof(blade_sample_type));
+ return to_read;
+ }
+};
+
+using dev_buf_t = uhd_buf_wrap;
+using bh_fn_t = std::function<int(dev_buf_t *)>;
+
+template <typename T> struct uhd_hw {
+ uhd::usrp::multi_usrp::sptr dev;
+ uhd::rx_streamer::sptr rx_stream;
+ uhd::tx_streamer::sptr tx_stream;
+ blade_sample_type *one_pkt_buf;
+ std::vector<blade_sample_type *> pkt_ptrs;
+ size_t rx_spp;
+ double rxticks;
+ unsigned int rxFullScale, txFullScale;
+ int rxtxdelay;
+ float rxgain, txgain;
+
+ virtual ~uhd_hw()
+ {
+ delete[] one_pkt_buf;
+ }
+ uhd_hw() : rxFullScale(32767), txFullScale(32767), rxtxdelay(-67)
+ {
+ }
+
+ bool tuneTx(double freq, size_t chan = 0)
+ {
+ msleep(25);
+ dev->set_tx_freq(freq, chan);
+ msleep(25);
+ return true;
+ };
+ bool tuneRx(double freq, size_t chan = 0)
+ {
+ msleep(25);
+ dev->set_rx_freq(freq, chan);
+ msleep(25);
+ return true;
+ };
+ bool tuneRxOffset(double offset, size_t chan = 0)
+ {
+ return true;
+ };
+
+ double setRxGain(double dB, size_t chan = 0)
+ {
+ rxgain = dB;
+ msleep(25);
+ dev->set_rx_gain(dB, chan);
+ msleep(25);
+ return dB;
+ };
+ double setTxGain(double dB, size_t chan = 0)
+ {
+ txgain = dB;
+ msleep(25);
+ dev->set_tx_gain(dB, chan);
+ msleep(25);
+ return dB;
+ };
+ int setPowerAttenuation(int atten, size_t chan = 0)
+ {
+ return atten;
+ };
+
+ int init_device(bh_fn_t rxh, bh_fn_t txh)
+ {
+ auto const lock_delay_ms = 500;
+ auto const mcr = 26e6;
+ auto const rate = (1625e3 / 6) * 4;
+ auto const ref = "external";
+ auto const gain = 35;
+ auto const freq = 931.4e6; // 936.8e6
+ auto bw = 0.5e6;
+ auto const channel = 0;
+ std::string args = {};
+
+ dev = uhd::usrp::multi_usrp::make(args);
+ std::cout << "Using Device: " << dev->get_pp_string() << std::endl;
+ dev->set_clock_source(ref);
+ dev->set_master_clock_rate(mcr);
+ dev->set_rx_rate(rate, channel);
+ dev->set_tx_rate(rate, channel);
+ uhd::tune_request_t tune_request(freq, 0);
+ dev->set_rx_freq(tune_request, channel);
+ dev->set_rx_gain(gain, channel);
+ dev->set_tx_gain(60, channel);
+ dev->set_rx_bandwidth(bw, channel);
+ dev->set_tx_bandwidth(bw, channel);
+
+ while (!(dev->get_rx_sensor("lo_locked", channel).to_bool() &&
+ dev->get_mboard_sensor("ref_locked").to_bool()))
+ std::this_thread::sleep_for(std::chrono::milliseconds(lock_delay_ms));
+
+ uhd::stream_args_t stream_args("sc16", "sc16");
+ rx_stream = dev->get_rx_stream(stream_args);
+ uhd::stream_args_t stream_args2("sc16", "sc16");
+ tx_stream = dev->get_tx_stream(stream_args2);
+
+ rx_spp = rx_stream->get_max_num_samps();
+ rxticks = dev->get_rx_rate();
+ assert(rxticks == dev->get_tx_rate());
+ one_pkt_buf = new blade_sample_type[rx_spp];
+ pkt_ptrs = { 1, &one_pkt_buf[0] };
+ return 0;
+ }
+
+ void *rx_cb(bh_fn_t burst_handler)
+ {
+ void *ret;
+ static int to_skip = 0;
+
+ uhd::rx_metadata_t md;
+ auto num_rx_samps = rx_stream->recv(pkt_ptrs.front(), rx_spp, md, 3.0, true);
+
+ if (md.error_code == uhd::rx_metadata_t::ERROR_CODE_TIMEOUT) {
+ std::cerr << boost::format("Timeout while streaming") << std::endl;
+ exit(0);
+ }
+ if (md.error_code == uhd::rx_metadata_t::ERROR_CODE_OVERFLOW) {
+ std::cerr << boost::format("Got an overflow indication. Please consider the following:\n"
+ " Your write medium must sustain a rate of %fMB/s.\n"
+ " Dropped samples will not be written to the file.\n"
+ " Please modify this example for your purposes.\n"
+ " This message will not appear again.\n") %
+ 1.f;
+ exit(0);
+ ;
+ }
+ if (md.error_code != uhd::rx_metadata_t::ERROR_CODE_NONE) {
+ std::cerr << str(boost::format("Receiver error: %s") % md.strerror());
+ exit(0);
+ }
+
+ dev_buf_t rcd = { rxticks, num_rx_samps, &md, &one_pkt_buf[0] };
+
+ if (to_skip < 120) // prevents weird overflows on startup
+ to_skip++;
+ else {
+ burst_handler(&rcd);
+ }
+
+ return ret;
+ }
+
+ auto get_rx_burst_handler_fn(bh_fn_t burst_handler)
+ {
+ auto fn = [this, burst_handler] {
+ pthread_setname_np(pthread_self(), "rxrun");
+
+ uhd::stream_cmd_t stream_cmd(uhd::stream_cmd_t::STREAM_MODE_START_CONTINUOUS);
+ stream_cmd.stream_now = true;
+ stream_cmd.time_spec = uhd::time_spec_t();
+ rx_stream->issue_stream_cmd(stream_cmd);
+
+ while (1) {
+ rx_cb(burst_handler);
+ }
+ };
+ return fn;
+ }
+ auto get_tx_burst_handler_fn(bh_fn_t burst_handler)
+ {
+ auto fn = [] {
+ // dummy
+ };
+ return fn;
+ }
+ void submit_burst_ts(blade_sample_type *buffer, int len, uint64_t ts)
+ {
+ uhd::tx_metadata_t m = {};
+ m.end_of_burst = true;
+ m.start_of_burst = true;
+ m.has_time_spec = true;
+ m.time_spec = m.time_spec.from_ticks(ts + rxtxdelay, rxticks); // uhd specific b210 delay!
+ std::vector<void *> ptrs(1, buffer);
+
+ tx_stream->send(ptrs, len, m);
+
+ uhd::async_metadata_t async_md;
+ bool tx_ack = false;
+ while (!tx_ack && tx_stream->recv_async_msg(async_md)) {
+ tx_ack = (async_md.event_code == uhd::async_metadata_t::EVENT_CODE_BURST_ACK);
+ }
+ std::cout << (tx_ack ? "yay" : "nay") << " " << async_md.time_spec.to_ticks(rxticks) << std::endl;
+ }
+
+ void set_name_aff_sched(const char *name, int cpunum, int schedtype, int prio)
+ {
+ pthread_setname_np(pthread_self(), name);
+
+ cpu_set_t cpuset;
+
+ CPU_ZERO(&cpuset);
+ CPU_SET(cpunum, &cpuset);
+
+ auto rv = pthread_setaffinity_np(pthread_self(), sizeof(cpuset), &cpuset);
+ if (rv < 0) {
+ std::cerr << name << " affinity: errreur! " << std::strerror(errno);
+ return exit(0);
+ }
+
+ sched_param sch_params;
+ sch_params.sched_priority = prio;
+ rv = pthread_setschedparam(pthread_self(), schedtype, &sch_params);
+ if (rv < 0) {
+ std::cerr << name << " sched: errreur! " << std::strerror(errno);
+ return exit(0);
+ }
+ }
+}; \ No newline at end of file