diff --git a/aerpaw/client/uav_runner.py b/aerpaw/client/uav_runner.py
index 716f0ae..85322b1 100644
--- a/aerpaw/client/uav_runner.py
+++ b/aerpaw/client/uav_runner.py
@@ -46,8 +46,9 @@ class MessageType(IntEnum):
POSITION = 8
-AERPAW_DIR = Path(__file__).parent.parent
-CONFIG_FILE = AERPAW_DIR / "config" / "client.yaml"
+AERPAW_DIR = Path('/root/miSim/aerpaw')
+CONFIG_FILE = Path(os.environ.get('AERPAW_CLIENT_CONFIG',
+ AERPAW_DIR / "config" / "client.yaml"))
def load_config():
diff --git a/aerpaw/config/client.yaml b/aerpaw/config/client1.yaml
similarity index 65%
rename from aerpaw/config/client.yaml
rename to aerpaw/config/client1.yaml
index 517dd2b..75180e2 100644
--- a/aerpaw/config/client.yaml
+++ b/aerpaw/config/client1.yaml
@@ -1,5 +1,15 @@
# AERPAW UAV (Client) Configuration
+# Unique 0-indexed UAV identifier (each UAV must have a distinct value)
+uav_id: 0
+
+# TDM (Time-Division Multiplexing) radio settings
+# All UAVs share a common frequency; each transmits only during its time slot.
+# Slot assignment uses wall-clock modular arithmetic (GPS/NTP synced).
+tdm:
+ slot_duration: 0.5 # seconds per slot
+ guard_interval: 0.05 # seconds of silence at slot boundaries
+
# ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
origin:
lat: 35.72550610629396
diff --git a/aerpaw/config/client2.yaml b/aerpaw/config/client2.yaml
new file mode 100644
index 0000000..851c0dd
--- /dev/null
+++ b/aerpaw/config/client2.yaml
@@ -0,0 +1,38 @@
+# AERPAW UAV (Client) Configuration
+
+# Unique 0-indexed UAV identifier (each UAV must have a distinct value)
+uav_id: 1
+
+# TDM (Time-Division Multiplexing) radio settings
+# All UAVs share a common frequency; each transmits only during its time slot.
+# Slot assignment uses wall-clock modular arithmetic (GPS/NTP synced).
+tdm:
+ slot_duration: 0.5 # seconds per slot
+ guard_interval: 0.05 # seconds of silence at slot boundaries
+
+# ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
+origin:
+ lat: 35.72550610629396
+ lon: -78.70019657805574
+ alt: 0.0 # Alt=0 means ENU z directly becomes target altitude above home
+# Environment-specific settings
+environments:
+ local:
+ # MAVLink connection for SITL simulation (UDP)
+ mavlink:
+ ip: "127.0.0.1"
+ port: 14550
+ # Controller server address
+ controller:
+ ip: "127.0.0.1"
+ port: 5000
+
+ testbed:
+ # AERPAW testbed: E-VM listens, MAVLink Filter connects TO us (UDP)
+ mavlink:
+ ip: "192.168.32.26"
+ port: 14550
+ # Controller runs on host machine (192.168.122.1 from E-VM perspective)
+ controller:
+ ip: "192.168.122.1"
+ port: 5000
\ No newline at end of file
diff --git a/aerpaw/radio/CSwSNRRX.py b/aerpaw/radio/CSwSNRRX.py
new file mode 100644
index 0000000..4131ee6
--- /dev/null
+++ b/aerpaw/radio/CSwSNRRX.py
@@ -0,0 +1,529 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+
+#
+# SPDX-License-Identifier: GPL-3.0
+#
+# GNU Radio Python Flow Graph
+# Title: CSwSNRRX
+# Author: Ozgur Ozdemir
+# GNU Radio version: v3.8.5.0-6-g57bd109d
+
+from gnuradio import analog
+from gnuradio import blocks
+from gnuradio import digital
+from gnuradio import filter
+from gnuradio.filter import firdes
+from gnuradio import gr
+import sys
+import signal
+from argparse import ArgumentParser
+from gnuradio.eng_arg import eng_float, intx
+from gnuradio import eng_notation
+from gnuradio import uhd
+import time
+import epy_block_0
+import math
+import threading
+
+
+def derive_num_uavs_from_csv(csv_path=None):
+ """Derive number of UAVs from scenario.csv by counting initial positions.
+
+ The initialPositions column contains a quoted comma-separated list of
+ x,y,z triples. num_uavs = len(values) / 3.
+ """
+ import os, csv
+ if csv_path is None:
+ csv_path = '/root/miSim/aerpaw/config/scenario.csv'
+ with open(csv_path, 'r') as f:
+ reader = csv.reader(f, skipinitialspace=True)
+ header = [h.strip() for h in next(reader)]
+ row = next(reader)
+ col = header.index('initialPositions')
+ init_pos = row[col].strip()
+ n_vals = len([v.strip() for v in init_pos.split(',') if v.strip()])
+ if n_vals % 3 != 0:
+ raise ValueError(f"initialPositions has {n_vals} values; expected a multiple of 3")
+ return n_vals // 3
+
+
+class TdmTaggedFileSink(gr.sync_block):
+ """GNU Radio sink that writes CSV rows tagged with the current TDM TX
+ slot ID. Each row has the form: tx_uav_id,value
+
+ During the guard interval the TX ID is written as -1.
+ """
+
+ def __init__(self, filepath, num_uavs, slot_duration, guard_interval):
+ import numpy
+ gr.sync_block.__init__(
+ self,
+ name='TDM Tagged File Sink',
+ in_sig=[numpy.float32],
+ out_sig=None)
+ self._num_uavs = num_uavs
+ self._slot_duration = slot_duration
+ self._guard_interval = guard_interval
+ self._frame_duration = slot_duration * num_uavs
+ self._f = open(filepath, 'w')
+ self._f.write('tx_uav_id,value\n')
+
+ def work(self, input_items, output_items):
+ now = time.time()
+ slot_time = now % self._frame_duration
+ current_slot = int(slot_time / self._slot_duration)
+ time_into_slot = slot_time - current_slot * self._slot_duration
+
+ if time_into_slot < self._guard_interval:
+ tx_id = -1 # guard interval — ambiguous
+ else:
+ tx_id = current_slot
+
+ for val in input_items[0]:
+ self._f.write(f'{tx_id},{val}\n')
+
+ self._f.flush()
+ return len(input_items[0])
+
+ def stop(self):
+ self._f.close()
+ return True
+
+
+class CSwSNRRX(gr.top_block):
+
+ def __init__(self, args='', freq=3.32e9, gainrx=30, noise=8, offset=250e3, samp_rate=2e6, sps=16,
+ uav_id=0, num_uavs=1, slot_duration=0.5, guard_interval=0.05):
+ gr.top_block.__init__(self, "CSwSNRRX")
+
+ ##################################################
+ # Parameters
+ ##################################################
+ self.args = args
+ self.freq = freq
+ self.gainrx = gainrx
+ self.noise = noise
+ self.offset = offset
+ self.samp_rate = samp_rate
+ self.sps = sps
+ self.uav_id = uav_id
+ self.num_uavs = num_uavs
+ self.slot_duration = slot_duration
+ self.guard_interval = guard_interval
+
+ ##################################################
+ # Variables
+ ##################################################
+ self.nfilts = nfilts = 32
+ self.alpha = alpha = 0.99
+ self.rrc_taps = rrc_taps = firdes.root_raised_cosine(nfilts, nfilts*samp_rate,samp_rate/sps, alpha, 11*sps*nfilts)
+ self.lbc = lbc = 0.5
+ self.fun_prob = fun_prob = 0
+
+ ##################################################
+ # Blocks
+ ##################################################
+ self.AGCprob = blocks.probe_signal_f()
+ def _fun_prob_probe():
+ while True:
+
+ val = self.AGCprob.level()
+ try:
+ self.set_fun_prob(val)
+ except AttributeError:
+ pass
+ time.sleep(1.0 / (100))
+ _fun_prob_thread = threading.Thread(target=_fun_prob_probe)
+ _fun_prob_thread.daemon = True
+ _fun_prob_thread.start()
+
+ self.uhd_usrp_source_0 = uhd.usrp_source(
+ ",".join(("", args)),
+ uhd.stream_args(
+ cpu_format="fc32",
+ args='',
+ channels=list(range(0,1)),
+ ),
+ )
+ self.uhd_usrp_source_0.set_center_freq(freq, 0)
+ self.uhd_usrp_source_0.set_gain(gainrx, 0)
+ self.uhd_usrp_source_0.set_antenna('RX2', 0)
+ self.uhd_usrp_source_0.set_samp_rate(samp_rate)
+ self.uhd_usrp_source_0.set_time_unknown_pps(uhd.time_spec())
+ self.freq_xlating_fft_filter_ccc_0_0 = filter.freq_xlating_fft_filter_ccc(1, (-1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, 1, -1, -1, -1, -1, -1, 1, -1, 1, -1, -1, 1, -1, -1, -1, -1, 1, -1, 1, -1,
+ 1, -1, -1, 1, -1, -1, -1, 1, -1, -1, 1, -1, 1, 1, 1, -1, 1, -1, 1, -1, -1, -1, 1, 1, -1, -1, -1, 1, -1, -1, -1, 1, -1, -1, -1, -1, -1, 1, 1, -1, -1, -1, 1,
+ -1, 1, 1, 1, -1, -1, -1, 1, 1, -1, -1, -1, 1, 1, 1, -1, 1, -1, -1, 1, 1, 1, -1, 1, 1, 1, -1, 1, -1, -1, -1, -1, 1, 1, 1, 1, -1, 1, -1, -1, -1, -1, 1,
+ 1, -1, 1, -1, 1, -1, -1, 1, -1, -1, 1, -1, -1, -1, 1, -1, -1, -1, -1, 1, 1, 1, -1, -1, -1, -1, -1, -1, 1, 1, 1, -1, -1, 1, 1, 1, -1, 1, 1, -1, 1, -1, -1,
+ -1, -1, 1, -1, 1, -1, -1, 1, -1, 1, -1, -1, 1, -1, 1, 1, 1, 1, -1, 1, 1, -1, -1, 1, -1, 1, 1, 1, 1, -1, 1, -1, -1, -1, 1, -1, 1, -1, 1, -1, -1, 1, 1,
+ -1, -1, 1, -1, -1, -1, -1, -1, 1, 1, 1, 1, -1, 1, -1, 1, -1, -1, 1, 1, -1, -1, -1, -1, -1, -1, -1, -1, -1, 1, -1, 1, -1, -1, -1, 1, -1, -1, -1, 1, 1, -1, 1,
+ -1, -1, 1, -1, -1, -1, -1, -1, 1, 1, -1, 1, -1, 1, -1, 1, 1, -1, -1, 1, -1, 1, -1, -1, -1, -1, 1, -1, 1, 1, 1, 1, -1, 1, -1, 1, -1, 1, -1, 1, -1, -1, -1,
+ 1, 1, 1, 1, -1, 1, -1, -1, 1, -1, 1, 1, -1, 1, 1, 1, 1, -1, 1, 1, -1, 1, -1, -1, 1, 1, 1, -1, 1, -1, 1, -1, 1, -1, -1, 1, -1, -1, 1, 1, -1, -1, 1,
+ -1, -1, 1, -1, -1, 1, 1, 1, -1, -1, -1, -1, 1, 1, -1, 1, 1, -1, 1, -1, 1, -1, 1, -1, -1, 1, 1, -1, 1, 1, -1, -1, -1, -1, 1, 1, -1, 1, 1, 1, 1, -1, 1,
+ -1, 1, 1, -1, -1, 1, -1, -1, 1, -1, -1, -1, 1, 1, -1, -1, -1, 1, 1, -1, -1, 1, -1, -1, 1, -1, 1, 1, 1, 1, -1, -1, 1, -1, -1, 1, -1, -1, 1, -1, 1, -1, -1,
+ -1, -1, -1, 1, 1, 1, 1, 1, 1, -1, 1, -1, -1, -1, 1, 1, -1, -1, 1, -1, -1, -1, -1, 1, 1, 1, 1, 1, -1, -1, -1, -1, -1, -1, -1, 1, -1, -1, -1, 1, -1, 1, -1,
+ 1, -1, 1, 1, 1, -1, -1, 1, 1, -1, 1, -1, -1, -1, 1, 1, 1, -1, -1, -1, -1, -1, 1, 1, 1, 1, -1, -1, -1, 1, -1, -1, 1, -1, -1, 1, -1, -1, 1, -1, -1, -1, -1,
+ -1, -1, -1, -1, 1, -1, 1, 1, -1, -1, 1, -1, -1, 1, 1, -1, -1, 1, 1, -1, 1, -1, -1, 1, -1, 1, 1, -1, -1, 1, 1, 1, -1, 1, -1, -1, -1, -1, -1, -1, 1, 1, -1,
+ 1, 1, 1, 1, 1, 1, -1, 1, 1, -1, 1, 1, 1, -1, 1, 1, -1, -1, 1, 1, 1, -1, 1, 1, -1, -1, -1, -1, -1, -1, 1, 1, 1, 1, -1, 1, 1, 1, -1, -1, 1, 1, 1,
+ -1, 1, -1, -1, 1, -1, -1, -1, 1, 1, 1, 1, -1, 1, 1, -1, 1, -1, 1, 1, 1, 1, -1, 1, 1, 1, 1, 1, -1, 1, 1, -1, -1, 1, -1, -1, 1, 1, 1, -1, 1, 1, -1,
+ 1, 1, -1, -1, -1, 1, -1, -1, -1, 1, 1, -1, -1, -1, -1, 1, -1, -1, 1, -1, 1, 1, 1, 1, 1, -1, 1, -1, -1, 1, 1, -1, -1, -1, 1, 1, -1, -1, -1, -1, -1, 1, -1,
+ 1, -1, 1, -1, -1, -1, -1, -1, -1, 1, -1, 1, 1, 1, 1, 1, -1, -1, 1, -1, 1, 1, -1, 1, 1, -1, -1, -1, 1, 1, -1, -1, 1, 1, -1, 1, -1, 1, 1, -1, 1, 1, -1,
+ 1, 1, -1, 1, -1, -1, -1, -1, -1, -1, 1, -1, -1, 1, 1, 1, 1, -1, 1, 1, 1, 1, 1, 1, 1, 1, -1, -1, 1, 1, -1, -1, 1, 1, 1, 1, 1, -1, 1, -1, -1, 1, -1,
+ -1, -1, -1, 1, 1, 1, -1, 1, -1, -1, -1, -1, 1, -1, 1, 1, -1, 1, -1, 1, -1, 1, 1, 1, 1, 1, -1, 1, -1, 1, 1, 1, -1, -1, -1, -1, 1, 1, -1, -1, 1, -1, 1,
+ -1, 1, 1, 1, 1, -1, 1, -1, -1, 1, 1, -1, 1, -1, 1, 1, -1, -1, 1, -1, 1, 1, -1, -1, -1, 1, -1, -1, 1, -1, 1, -1, -1, -1, 1, -1, 1, 1, 1, 1, -1, 1, 1,
+ 1, -1, 1, -1, 1, 1, -1, 1, 1, 1, -1, 1, -1, 1, -1, 1, 1, 1, 1, -1, -1, 1, -1, 1, 1, -1, -1, 1, -1, -1, -1, 1, -1, -1, 1, 1, 1, 1, 1, -1, 1, 1, 1,
+ 1, -1, -1, -1, 1, -1, -1, -1, -1, -1, 1, -1, -1, -1, -1, 1, -1, -1, 1, -1, -1, -1, 1, 1, 1, -1, -1, 1, 1, -1, 1, 1, 1, -1, 1, 1, 1, 1, 1, 1, 1, -1, -1,
+ -1, 1, 1, -1, 1, 1, -1, 1, 1, -1, -1, 1, -1, -1, -1, -1, 1, -1, 1, 1, 1, -1, -1, 1, -1, 1, -1, -1, -1, -1, -1, -1, 1, 1, 1, 1, 1, 1, 1, 1, -1, -1, -1,
+ 1, -1, -1, 1, 1, -1, 1, -1, -1, 1, 1, -1, 1, -1, -1, 1, -1, -1, 1, -1, -1, 1, 1, -1, -1, -1, -1, -1, 1, -1, -1, -1, 1, -1, -1, -1, 1, -1, 1, 1, -1, -1, 1,
+ 1, 1, 1, 1, -1, -1, -1, -1, 1, -1, -1, 1, -1, -1, 1, 1, 1, 1, -1, -1, -1, 1, 1, 1, 1, -1, -1, 1, 1, 1, -1, 1, -1, 1, 1, -1, -1, -1, 1, -1, 1, -1, -1,
+ 1, -1, -1, 1, -1, 1, -1, 1, -1, -1, -1, 1, 1, -1, 1, -1, 1, -1, -1, -1, -1, -1, 1, -1, -1, 1, 1, 1, -1, -1, 1, 1, 1, 1, -1, 1, -1, 1, -1, 1, 1, 1, -1,
+ -1, -1, 1, -1, 1, -1, -1, 1, 1, -1, 1, -1, 1, -1, -1, -1, 1, -1, 1, -1, -1, 1, -1, 1, 1, -1, 1, -1, 1, 1, -1, 1, 1, 1, 1, 1, -1, 1, -1, 1, -1, 1, -1,
+ -1, -1, -1, -1, 1, 1, -1, 1, 1, 1, -1, 1, 1, -1, 1, 1, 1, 1, -1, 1, -1, -1, 1, -1, -1, 1, -1, 1, 1, 1, -1, -1, -1, 1, -1, -1, -1, -1, 1, 1, -1, -1, -1,
+ -1, -1, -1, 1, 1, -1, 1, -1, 1, 1, 1, 1, -1, -1, 1, 1, 1, 1, -1, -1, 1, 1, -1, 1, 1, -1, 1, 1, 1, 1, 1, -1, -1, -1, 1, -1, 1, -1, 1, -1, 1, -1, 1,
+ -1, -1, 1, 1, 1, 1, 1, -1, -1, -1, 1, 1, -1, -1, 1, -1, 1, 1, -1, 1, 1, 1, -1, -1, 1, 1, -1, 1, 1, -1, -1, 1, 1, 1, 1, -1, 1, -1, -1, -1, 1, 1, 1,
+ -1, 1, -1, -1, -1, 1, 1, -1, 1, 1, -1, -1, -1, -1, -1, 1, -1, 1, 1, 1, -1, -1, -1, -1, 1, -1, -1, -1, 1, -1, 1, 1, 1, -1, 1, 1, 1, 1, -1, -1, 1, -1, -1,
+ -1, -1, -1, 1, -1, 1, 1, -1, 1, -1, -1, -1, 1, 1, 1, 1, -1, -1, -1, -1, 1, -1, 1, -1, -1, -1, 1, 1, -1, -1, 1, 1, -1, -1, -1, 1, 1, -1, 1, -1, -1, -1, 1,
+ -1, -1, -1, -1, -1, -1, 1, -1, -1, -1, 1, 1, 1, -1, 1, -1, 1, -1, 1, 1, -1, 1, -1, -1, 1, -1, -1, 1, 1, -1, 1, 1, -1, -1, 1, -1, 1, 1, -1, 1, -1, 1, -1,
+ -1, 1, 1, 1, 1, -1, -1, -1, -1, 1, 1, 1, -1, -1, -1, 1, -1, -1, 1, 1, 1, 1, -1, -1, 1, 1, 1, 1, 1, -1, 1, 1, -1, 1, -1, -1, -1, 1, 1, -1, 1, -1, -1,
+ -1, -1, -1, -1, -1, -1, -1, 1, 1, 1, -1, -1, -1, 1, 1, -1, 1, 1, 1, 1, 1, -1, -1, 1, 1, -1, 1, -1, 1, 1, 1, 1, 1, -1, 1, 1, 1, 1, 1, -1, -1, 1, -1,
+ -1, 1, -1, 1, 1, -1, 1, -1, -1, 1, -1, 1, 1, 1, -1, 1, 1, 1, -1, -1, -1, 1, -1, -1, 1, -1, 1, 1, -1, -1, 1, -1, 1, -1, 1, -1, -1, 1, -1, 1, -1, 1, -1,
+ -1, 1, 1, 1, -1, 1, -1, -1, -1, 1, -1, -1, 1, 1, -1, -1, 1, -1, 1, 1, -1, -1, 1, 1, -1, -1, 1, -1, -1, -1, 1, -1, 1, 1, 1, 1, 1, 1, 1, 1, -1, 1, 1,
+ 1, -1, -1, 1, -1, 1, -1, 1, -1, -1, -1, -1, 1, -1, 1, -1, 1, 1, -1, 1, -1, -1, -1, -1, -1, 1, 1, -1, -1, 1, 1, -1, 1, 1, 1, 1, -1, 1, 1, 1, 1, -1, -1,
+ 1, 1, -1, -1, -1, -1, 1, 1, 1, -1, -1, 1, 1, -1, -1, 1, 1, -1, 1, 1, -1, 1, -1, 1, 1, 1, -1, -1, 1, 1, 1, 1, -1, -1, -1, 1, -1, 1, 1, -1, -1, 1, -1,
+ 1, 1, 1, -1, -1, 1, -1, -1, -1, -1, -1, -1, -1, 1, 1, -1, 1, 1, -1, 1, 1, 1, -1, 1, -1, -1, -1, 1, 1, 1, 1, 1, -1, -1, -1, 1, -1, -1, -1, 1, -1, 1, -1,
+ -1, -1, 1, 1, 1, -1, 1, 1, -1, -1, 1, 1, -1, -1, 1, 1, -1, -1, 1, -1, 1, -1, 1, -1, 1, 1, -1, 1, -1, 1, 1, -1, -1, 1, 1, 1, 1, -1, -1, -1, -1, -1, 1,
+ 1, -1, -1, -1, -1, -1, 1, 1, 1, -1, 1, -1, -1, 1, -1, 1, -1, 1, 1, 1, 1, 1, 1, -1, -1, 1, 1, 1, 1, 1, 1, 1, 1, -1, 1, -1, 1, -1, -1, 1, -1, -1, -1,
+ -1, -1, -1, 1, -1, 1, -1, 1, 1, 1, -1, -1, -1, -1, -1, 1, -1, -1, 1, -1, -1, -1, -1, 1, 1, -1, -1, 1, -1, -1, -1, 1, 1, 1, 1, 1, 1, 1, -1, 1, -1, -1, 1,
+ -1, 1, -1, -1, 1, 1, 1, 1, 1, 1, -1, -1, 1, 1, -1, 1, 1, 1, 1, 1, 1, 1, 1, 1, -1, 1, 1, -1, -1, -1, 1, -1, 1, 1, 1, 1, -1, -1, 1, 1, -1, 1, -1,
+ -1, 1, 1, 1, 1, -1, -1, 1, -1, 1, 1, 1, -1, 1, -1, -1, -1, -1, -1, 1, 1, 1, -1, 1, 1, -1, 1, -1, 1, -1, -1, 1, -1, 1, 1, -1, -1, -1, 1, 1, -1, 1, -1,
+ 1, -1, 1, -1, -1, -1, 1, -1, 1, 1, -1, 1, -1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, -1, -1, -1, -1, -1, -1, 1, 1, -1, -1, -1, 1, 1, 1, 1, 1, -1, -1,
+ 1, 1, -1, -1, -1, 1, 1, 1, 1, -1, -1, -1, 1, 1, -1, 1, -1, -1, 1, 1, -1, -1, -1, -1, 1, -1, -1, -1, -1, 1, 1, 1, 1, -1, -1, -1, -1, -1, -1, 1, -1, -1, -1,
+ -1, 1, 1, -1, 1, -1, -1, -1, -1, 1, -1, -1, -1, -1, 1, -1, 1, 1, -1, -1, -1, 1, -1, 1, 1, -1, 1, -1, -1, 1, 1, 1, 1, 1, -1, 1, -1, 1, 1, -1, -1, -1, -1,
+ -1, 1, -1, -1, 1, 1, -1, -1, -1, 1, 1, 1, -1, -1, -1, -1, 1, 1, 1, 1, 1, -1, 1, -1, -1, -1, -1, -1, -1, -1, 1, -1, 1, 1, 1, -1, 1, -1, -1, 1, -1, -1, 1,
+ 1, 1, 1, 1, -1, -1, 1, 1, 1, -1, -1, 1, 1, 1, -1, -1, 1, -1, 1, -1, -1, 1, -1, -1, -1, 1, 1, -1, 1, -1, 1, 1, -1, -1, -1, -1, 1, 1, -1, -1, 1, 1, 1,
+ -1, 1, 1, 1, -1, -1, -1, -1, -1, -1, 1, -1, 1, -1, -1, 1, 1, -1, -1, -1, 1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, 1, 1, -1, -1, -1, -1, 1, 1, 1, 1, -1, 1,
+ 1, -1, -1, -1, 1, 1, 1, 1, 1, 1, -1, 1, 1, -1, -1, 1, 1, -1, 1, 1, 1, -1, -1, 1, 1, 1, 1, 1, -1, -1, 1, -1, 1, -1, -1, 1, 1, -1, -1, 1, 1, -1, -1,
+ -1, -1, 1, -1, 1, -1, -1, 1, 1, 1, -1, -1, 1, -1, -1, 1, -1, 1, -1, -1, 1, -1, -1, 1, 1, 1, -1, 1, -1, -1, 1, 1, -1, -1, 1, 1, 1, -1, -1, -1, 1, -1, -1,
+ -1, 1, 1, 1, -1, -1, -1, 1, -1, 1, 1, 1, 1, 1, -1, 1, 1, -1, 1, 1, -1, -1, 1, 1, -1, -1, -1, 1, -1, -1, 1, -1, -1, -1, -1, -1, 1, -1, -1, 1, -1, 1, -1,
+ -1, 1, 1, -1, 1, 1, 1, -1, -1, -1, 1, 1, 1, 1, -1, 1, 1, 1, 1, -1, 1, 1, 1, -1, -1, -1, 1, 1, -1, 1, -1, 1, 1, 1, -1, -1, -1, 1, 1, 1, -1, -1, 1,
+ 1, 1, 1, 1, 1, -1, 1, -1, 1, -1, 1, 1, -1, -1, -1, -1, 1, -1, -1, -1, 1, 1, 1, 1, 1, -1, 1, -1, 1, -1, -1, -1, -1, -1, -1, -1, -1, 1, 1, 1, 1, -1, -1,
+ 1, 1, -1, -1, 1, -1, 1, 1, 1, -1, 1, 1, -1, -1, -1, -1, 1, -1, 1, 1, 1, 1, 1, 1, -1, 1, -1, 1, 1, 1, 1, -1, -1, -1, 1, 1, 1, -1, -1, -1, 1, 1, 1,
+ 1, 1, 1, 1, 1, 1, -1, -1, 1, -1, -1, -1, 1, 1, 1, -1, 1, 1, 1, -1, 1, 1, -1, -1, -1, 1, 1, -1, 1, 1, 1, -1, 1, -1, -1, 1, 1, 1, 1, 1, 1, 1, -1,
+ 1, 1, -1, 1, -1, 1, -1, 1, 1, -1, 1, 1, -1, 1, -1, -1, 1, -1, -1, -1, 1, -1, 1, 1, -1, 1, 1, 1, 1, 1, 1, 1, -1, 1, -1, 1, 1, -1, 1, -1, -1, -1, 1,
+ -1, 1, 1, -1, -1, -1, 1, 1, 1, 1, -1, 1, -1, 1, 1, -1, 1, 1, -1, -1, 1, -1, 1, -1, -1, 1, -1, 1, -1, 1, 1, -1, 1, 1, 1, -1, -1, -1, 1, -1, 1, 1, -1,
+ 1, 1, -1, 1, 1, 1, 1, -1, -1, -1, -1, 1, -1, -1, -1, -1, -1, 1, 1, 1, -1, -1, 1, -1, 1, -1, 1, 1, -1, -1, -1, 1, -1, -1, -1, -1, 1, -1, -1, -1, -1, -1, -1,
+ 1, 1, -1, -1, 1, 1, 1, 1, 1, 1, 1, -1, -1, 1, -1, 1, -1, 1, 1, 1, -1, -1, 1, -1, -1, 1, -1, -1, -1, -1, 1, -1, -1, -1, 1, -1, -1, 1, 1, -1, 1, 1, -1,
+ 1, 1, -1, 1, 1, -1, -1, -1, -1, -1, -1, -1, 1, 1, 1, -1, 1, -1, 1, 1, -1, 1, -1, 1, -1, 1, -1, 1, 1, 1, -1, 1, 1, 1, -1, 1, -1, 1, -1, -1, 1, 1, 1,
+ -1, -1, -1, -1, -1, 1, -1, 1, 1, -1, -1, -1, -1, -1, 1, 1, -1, 1, 1, -1, -1, 1, 1, -1, 1, -1, 1, -1, -1, 1, 1, -1, 1, -1, -1, -1, -1, -1, 1, -1, -1, -1, 1,
+ 1, -1, -1, 1, -1, 1, -1, -1, 1, 1, 1, -1, 1, 1, -1, -1, 1, -1, -1, -1, 1, 1, -1, 1, 1, 1, 1, -1, -1, -1, 1, 1, -1, -1, -1, -1, 1, 1, -1, 1, -1, 1, 1,
+ -1, 1, -1, -1, 1, 1, -1, 1, 1, -1, 1, -1, -1, 1, 1, -1, -1, 1, -1, 1, -1, -1, -1, 1, 1, -1, 1, 1, 1, -1, -1, -1, -1, 1, 1, 1, -1, 1, -1, 1, -1, -1, 1,
+ -1, 1, -1, -1, -1, -1, 1, 1, 1, 1, 1, 1, -1, -1, -1, -1, -1, 1, 1, 1, -1, -1, -1, -1, 1, -1, 1, 1, 1, -1, 1, 1, -1, 1, -1, -1, 1, -1, 1, -1, 1, -1, 1,
+ 1, 1, 1, -1, 1, 1, -1, 1, 1, -1, 1, 1, 1, -1, -1, -1, -1, -1, 1, 1, -1, 1, -1, -1, -1, 1, 1, -1, -1, -1, -1, -1, -1, -1, 1, -1, 1, -1, 1, -1, 1, -1, -1,
+ -1, -1, 1, 1, 1, -1, 1, 1, -1, -1, -1, 1, -1, -1, 1, 1, 1, -1, -1, -1, 1, 1, 1, -1, 1, 1, 1, 1, 1, 1, -1, -1, -1, -1, 1, 1, 1, 1, -1, -1, 1, -1, -1,
+ -1, 1, -1, 1, -1, 1, 1, 1, 1, 1, -1, -1, -1, 1, 1, 1, -1, 1, -1, 1, 1, 1, 1, -1, 1, -1, 1, 1, 1, -1, 1, -1, -1, 1, 1, -1, 1, 1, 1, 1, -1, -1, 1,
+ 1, 1, -1, -1, -1, 1, 1, -1, -1, 1, 1, 1, 1, -1, 1, 1, -1, -1, 1, 1, 1, 1, 1, 1, -1, -1, -1, 1, -1, 1, 1, 1, -1, 1, -1, 1, 1, -1, -1, 1, 1, -1, 1,
+ -1, -1, -1, -1, 1, 1, -1, -1, -1, 1, -1, -1, 1, 1, -1, -1, -1, -1, 1, 1, -1, -1, -1, 1, 1, -1, 1, 1, -1, -1, 1, -1, -1, 1, -1, 1, -1, 1, 1, -1, -1, 1, 1,
+ -1, -1, -1, -1, -1, -1, 1, -1, -1, 1, -1, 1, 1, -1, 1, 1, -1, 1, -1, 1, 1, -1, -1, -1, 1, 1, 1, -1, -1, 1, -1, 1, 1, 1, 1, -1, -1, -1, -1, -1, 1, -1, -1,
+ -1, -1, -1, -1, -1, 1, -1, -1, 1, 1, -1, 1, -1, 1, 1, 1, -1, 1, -1, 1, 1, 1, -1, 1, 1, -1, 1, 1, -1, 1, -1, 1, -1, -1, -1, -1, 1, 1, -1, -1, 1, 1, -1,
+ -1, 1, 1, 1, -1, 1, -1, 1, -1, -1, -1, -1, 1, -1, -1, -1, 1, 1, -1, 1, 1, -1, 1, -1, -1, -1, 1, -1, -1, 1, -1, -1, -1, 1, -1, 1, -1, -1, 1, 1, 1, 1, -1,
+ 1, -1, -1, 1, 1, 1, 1, -1, 1, 1, -1, 1, 1, 1, 1, 1, 1, -1, -1, 1, -1, 1, 1, 1, 1, 1, -1, -1, -1, -1, 1, 1, -1, 1, -1, -1, 1, -1, 1, -1, -1, -1, 1,
+ 1, 1, 1, 1, 1, -1, -1, 1, -1, -1, 1, 1, 1, 1, -1, 1, -1, 1, 1, 1, 1, 1, -1, -1, 1, 1, 1, 1, -1, 1, 1, 1, -1, 1, 1, 1, 1, -1, 1, 1, -1, -1, -1, -1, 1, 1, 1, 1, 1, 1, 1, -1, -1, -1, -1, 1, -1, 1, 1, -1, -1, 1, 1, -1, 1, 1, -1, -1, -1, 1, 1, 1, -1, 1, 1, -1, 1, 1, 1, -1, -1, 1, -1, -1, 1, 1, -1, -1, -1, 1, -1, 1, -1, -1, -1, -1, -1, 1, -1, 1, 1, 1, 1, -1, -1, -1, 1, -1, 1, -1, -1, -1, 1, -1, 1, -1, 1, 1, -1, 1, 1, -1, -1, -1, -1, 1, -1, -1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, -1, 1, -1, -1, -1, -1, 1, -1, -1, 1, -1, 1, -1, 1, 1, 1, -1, 1, 1, -1, -1, 1, -1, 1, -1, 1, 1, -1, 1, -1, 1, -1, -1, -1, 1, 1, 1, -1, -1, 1, -1, -1, 1, 1, 1, -1, -1, 1, -1, 1, 1, -1, 1, -1, -1, -1, -1, 1, 1, 1, -1, -1, 1, -1, -1, -1, 1, 1, -1, -1, 1, 1, 1, -1, -1, 1, 1, -1, -1, -1, 1, -1, 1, 1, -1, -1, -1, -1, 1, 1, 1, -1, 1, 1, 1, -1, -1, 1, -1, -1, -1, 1, -1, -1, -1, 1, 1, 1, 1, -1, -1, 1, -1, 1, -1, 1, -1, 1, -1, -1, 1, -1, 1, 1, 1, -1, -1, 1, 1, -1, -1, -1, -1, -1, 1, 1, -1, -1, 1, -1, -1, 1, 1, 1, 1, 1, 1, -1, 1, 1, 1, -1, 1, 1, -1, 1, -1, 1, 1, -1, 1, -1, 1, 1, 1, -1, 1, 1, 1, 1, 1, -1, 1, -1, -1, -1, 1, -1, -1, -1, 1, -1, -1, 1, -1, -1, 1, 1, -1, 1, -1, -1, -1, 1, -1, 1, -1, -1, -1, -1, 1, 1, -1, 1, 1, 1, -1, -1, 1, -1, 1, 1, 1, -1, -1, -1, -1, -1, -1, -1, -1, 1, -1, -1, 1, -1, -1, 1, -1, 1, 1, -1, -1, -1, -1, 1, -1, 1, -1, 1, 1, 1, 1, -1, -1, -1, -1, 1, 1, -1, -1, -1, -1, 1, -1, 1, 1, -1, 1, 1, 1, -1, 1, 1, 1, -1, 1, 1, 1, -1, -1, 1, 1, -1, -1, 1, -1, -1, 1, 1, -1, 1, 1, 1, -1, 1, -1, 1, 1, 1, 1, 1, 1, -1, 1, 1, 1, 1, 1, 1, -1, 1, -1, -1, 1, 1, 1, -1, -1, 1, 1, -1, 1, -1, 1, -1, 1, 1, 1, -1, 1, -1, 1, -1, 1, -1, 1, 1, -1, -1, 1, 1, 1, -1, -1, -1, -1, -1, -1, -1, 1, 1, -1, -1, 1, -1, 1, 1, 1, 1, 1, 1, -1, -1, -1, 1, 1, 1, 1, 1, -1, 1, 1, 1, -1, -1, -1, -1, 1, -1, 1, -1, 1, -1, 1, 1, -1, -1, -1, 1, 1, -1, -1, -1, 1, -1, 1, -1, 1, -1, -1, -1, 1, -1, -1, 1, -1, 1, -1, 1, -1, 1, -1, 1, 1, -1, 1, 1, 1, 1, -1, -1, 1, -1, 1, -1, -1, -1, 1, -1, -1, 1, 1, 1, -1, 1, -1, 1, 1, 1, -1, -1, 1, -1, 1, 1, -1, -1, -1, -1, -1, -1, 1, -1, 1, 1, -1, 1, 1, -1, -1, 1, 1, 1, -1, -1, 1, -1, -1, -1, -1, 1, -1, -1, 1, 1, -1, -1, 1, 1, 1, 1, -1, -1, 1, -1, -1, 1, 1, -1, 1, -1, 1, -1, 1, -1, 1, -1, 1, -1, 1, 1, 1, 1, 1, 1, 1, -1, 1, 1, 1, 1, -1, 1, -1, 1, -1, -1, -1, 1, -1, -1, -1, -1, 1, -1, 1, -1, -1, -1, -1, 1, -1, -1, 1, 1, 1, -1, 1, 1, 1, 1, 1, -1, -1, -1, -1, -1, 1, -1, 1, -1, -1, -1, -1, -1, -1, -1, 1, 1, 1, 1, 1, -1, 1, 1, -1, -1, -1, -1, -1, 1, 1, 1, 1, 1, -1, -1, 1, -1, -1, -1, -1, 1, 1, -1, 1, 1, -1, -1, -1, 1, -1, 1, -1, 1, 1, -1, -1, 1, -1, -1, -1, -1, -1, -1, 1, 1, 1, -1, 1, 1, 1, 1, -1, 1, -1, -1, -1, -1, -1, 1, -1, 1, -1, 1, 1, -1, -1, -1, -1, -1, -1, -1, -1, 1, 1, -1, 1, -1, -1, 1, 1, 1, -1, -1, -1, 1, -1, 1, -1, 1, 1, 1, -1, 1, -1, -1, -1, 1, -1, 1, 1, 1, -1, -1, 1, 1, 1, -1, -1, -1, -1, 1, -1, -1, 1, 1, -1, 1, 1, 1, 1, 1, -1, 1, 1, 1, -1, 1, -1, -1, 1, -1, 1, 1, 1, 1, 1, 1, 1, -1, -1, 1, 1, 1, -1, 1, 1, 1, 1), 0, samp_rate/sps)
+ self.freq_xlating_fft_filter_ccc_0_0.set_nthreads(8)
+ self.freq_xlating_fft_filter_ccc_0_0.declare_sample_delay(0)
+ self.epy_block_0 = epy_block_0.blk(example_param=1)
+ self.digital_symbol_sync_xx_0 = digital.symbol_sync_cc(
+ digital.TED_SIGNAL_TIMES_SLOPE_ML,
+ sps,
+ 0.045,
+ 1.0,
+ 1.0,
+ 1.5,
+ 1,
+ digital.constellation_bpsk().base(),
+ digital.IR_PFB_MF,
+ nfilts,
+ rrc_taps)
+ self.digital_fll_band_edge_cc_0_0 = digital.fll_band_edge_cc(sps, alpha, sps*2+1, 2*math.pi/sps/100)
+ self.digital_costas_loop_cc_0 = digital.costas_loop_cc(lbc, 2, False)
+ self.blocks_vector_to_stream_0_0 = blocks.vector_to_stream(gr.sizeof_gr_complex*1, 4095)
+ self.blocks_sub_xx_0 = blocks.sub_ff(1)
+ self.blocks_stream_to_vector_0_0 = blocks.stream_to_vector(gr.sizeof_gr_complex*1, 4095)
+ self.blocks_nlog10_ff_0_0_0 = blocks.nlog10_ff(20, 1, 0)
+ self.blocks_nlog10_ff_0_0 = blocks.nlog10_ff(20, 1, 0)
+ self.blocks_multiply_xx_1 = blocks.multiply_vcc(1)
+ self.blocks_multiply_xx_0 = blocks.multiply_vcc(1)
+ self.blocks_moving_average_xx_1_0 = blocks.moving_average_cc(1000, 1/1000, 4000, 1)
+ self.blocks_moving_average_xx_1 = blocks.moving_average_cc(3, 1, 4000, 1)
+ self.blocks_moving_average_xx_0_0 = blocks.moving_average_ff(sps, 1, 4000, 1)
+ self.blocks_moving_average_xx_0 = blocks.moving_average_ff(sps, 1, 4000, 1)
+ self.blocks_keep_m_in_n_1_0 = blocks.keep_m_in_n(gr.sizeof_gr_complex, 1, 1000, 999)
+ self.blocks_keep_m_in_n_1 = blocks.keep_m_in_n(gr.sizeof_gr_complex, 1, 3, 2)
+ self.blocks_keep_m_in_n_0_0 = blocks.keep_m_in_n(gr.sizeof_gr_complex, 1000, 4095, 2000)
+ self.blocks_keep_m_in_n_0 = blocks.keep_m_in_n(gr.sizeof_gr_complex, 3, 4095, 1)
+ self.blocks_float_to_complex_0 = blocks.float_to_complex(1)
+ self.blocks_file_sink_0_0_0_0 = TdmTaggedFileSink(
+ '/root/SNR', num_uavs, slot_duration, guard_interval)
+ self.blocks_file_sink_0_0_0 = TdmTaggedFileSink(
+ '/root/Quality', num_uavs, slot_duration, guard_interval)
+ self.blocks_file_sink_0 = TdmTaggedFileSink(
+ '/root/Power', num_uavs, slot_duration, guard_interval)
+ self.blocks_divide_xx_0 = blocks.divide_ff(1)
+ self.blocks_complex_to_real_0_0 = blocks.complex_to_real(1)
+ self.blocks_complex_to_real_0 = blocks.complex_to_real(1)
+ self.blocks_complex_to_mag_0_0_0 = blocks.complex_to_mag(1)
+ self.blocks_complex_to_mag_0_0 = blocks.complex_to_mag(1)
+ self.blocks_add_const_vxx_0_0 = blocks.add_const_ff(-noise)
+ self.blocks_add_const_vxx_0 = blocks.add_const_ff(-gainrx)
+ self.analog_sig_source_x_0 = analog.sig_source_c(samp_rate, analog.GR_COS_WAVE, -offset, 1, 0, 0)
+ self.analog_const_source_x_0_0 = analog.sig_source_f(0, analog.GR_CONST_WAVE, 0, 0, fun_prob)
+ self.analog_const_source_x_0 = analog.sig_source_f(0, analog.GR_CONST_WAVE, 0, 0, 0)
+ self.analog_agc_xx_0 = analog.agc_cc(1e-4, 1.0, 1.0)
+ self.analog_agc_xx_0.set_max_gain(65536)
+ ##################################################
+ # Connections
+ ##################################################
+ self.connect((self.analog_agc_xx_0, 0), (self.blocks_complex_to_real_0, 0))
+ self.connect((self.analog_agc_xx_0, 0), (self.digital_fll_band_edge_cc_0_0, 0))
+ self.connect((self.analog_const_source_x_0, 0), (self.blocks_float_to_complex_0, 1))
+ self.connect((self.analog_const_source_x_0_0, 0), (self.blocks_float_to_complex_0, 0))
+ self.connect((self.analog_sig_source_x_0, 0), (self.blocks_multiply_xx_0, 1))
+ self.connect((self.blocks_add_const_vxx_0, 0), (self.blocks_add_const_vxx_0_0, 0))
+ self.connect((self.blocks_add_const_vxx_0, 0), (self.blocks_file_sink_0, 0))
+ self.connect((self.blocks_add_const_vxx_0_0, 0), (self.blocks_file_sink_0_0_0_0, 0))
+ self.connect((self.blocks_complex_to_mag_0_0, 0), (self.blocks_nlog10_ff_0_0, 0))
+ self.connect((self.blocks_complex_to_mag_0_0_0, 0), (self.blocks_nlog10_ff_0_0_0, 0))
+ self.connect((self.blocks_complex_to_real_0, 0), (self.blocks_moving_average_xx_0_0, 0))
+ self.connect((self.blocks_complex_to_real_0_0, 0), (self.blocks_moving_average_xx_0, 0))
+ self.connect((self.blocks_divide_xx_0, 0), (self.AGCprob, 0))
+ self.connect((self.blocks_float_to_complex_0, 0), (self.blocks_multiply_xx_1, 1))
+ self.connect((self.blocks_keep_m_in_n_0, 0), (self.blocks_moving_average_xx_1, 0))
+ self.connect((self.blocks_keep_m_in_n_0_0, 0), (self.blocks_moving_average_xx_1_0, 0))
+ self.connect((self.blocks_keep_m_in_n_1, 0), (self.blocks_complex_to_mag_0_0, 0))
+ self.connect((self.blocks_keep_m_in_n_1_0, 0), (self.blocks_complex_to_mag_0_0_0, 0))
+ self.connect((self.blocks_moving_average_xx_0, 0), (self.blocks_divide_xx_0, 0))
+ self.connect((self.blocks_moving_average_xx_0_0, 0), (self.blocks_divide_xx_0, 1))
+ self.connect((self.blocks_moving_average_xx_1, 0), (self.blocks_keep_m_in_n_1, 0))
+ self.connect((self.blocks_moving_average_xx_1_0, 0), (self.blocks_keep_m_in_n_1_0, 0))
+ self.connect((self.blocks_multiply_xx_0, 0), (self.analog_agc_xx_0, 0))
+ self.connect((self.blocks_multiply_xx_0, 0), (self.blocks_complex_to_real_0_0, 0))
+ self.connect((self.blocks_multiply_xx_1, 0), (self.freq_xlating_fft_filter_ccc_0_0, 0))
+ self.connect((self.blocks_nlog10_ff_0_0, 0), (self.blocks_add_const_vxx_0, 0))
+ self.connect((self.blocks_nlog10_ff_0_0, 0), (self.blocks_sub_xx_0, 0))
+ self.connect((self.blocks_nlog10_ff_0_0_0, 0), (self.blocks_sub_xx_0, 1))
+ self.connect((self.blocks_stream_to_vector_0_0, 0), (self.epy_block_0, 0))
+ self.connect((self.blocks_sub_xx_0, 0), (self.blocks_file_sink_0_0_0, 0))
+ self.connect((self.blocks_vector_to_stream_0_0, 0), (self.blocks_keep_m_in_n_0, 0))
+ self.connect((self.blocks_vector_to_stream_0_0, 0), (self.blocks_keep_m_in_n_0_0, 0))
+ self.connect((self.digital_costas_loop_cc_0, 0), (self.blocks_multiply_xx_1, 0))
+ self.connect((self.digital_fll_band_edge_cc_0_0, 0), (self.digital_symbol_sync_xx_0, 0))
+ self.connect((self.digital_symbol_sync_xx_0, 0), (self.digital_costas_loop_cc_0, 0))
+ self.connect((self.epy_block_0, 0), (self.blocks_vector_to_stream_0_0, 0))
+ self.connect((self.freq_xlating_fft_filter_ccc_0_0, 0), (self.blocks_stream_to_vector_0_0, 0))
+ self.connect((self.uhd_usrp_source_0, 0), (self.blocks_multiply_xx_0, 0))
+
+
+ def get_args(self):
+ return self.args
+
+ def set_args(self, args):
+ self.args = args
+
+ def get_freq(self):
+ return self.freq
+
+ def set_freq(self, freq):
+ self.freq = freq
+ self.uhd_usrp_source_0.set_center_freq(self.freq, 0)
+
+ def get_gainrx(self):
+ return self.gainrx
+
+ def set_gainrx(self, gainrx):
+ self.gainrx = gainrx
+ self.blocks_add_const_vxx_0.set_k(-self.gainrx)
+ self.uhd_usrp_source_0.set_gain(self.gainrx, 0)
+ self.uhd_usrp_source_0.set_gain(self.gainrx, 1)
+
+ def get_noise(self):
+ return self.noise
+
+ def set_noise(self, noise):
+ self.noise = noise
+ self.blocks_add_const_vxx_0_0.set_k(-self.noise)
+
+ def get_offset(self):
+ return self.offset
+
+ def set_offset(self, offset):
+ self.offset = offset
+ self.analog_sig_source_x_0.set_frequency(-self.offset)
+
+ def get_samp_rate(self):
+ return self.samp_rate
+
+ def set_samp_rate(self, samp_rate):
+ self.samp_rate = samp_rate
+ self.set_rrc_taps(firdes.root_raised_cosine(self.nfilts, self.nfilts*self.samp_rate, self.samp_rate/self.sps, self.alpha, 11*self.sps*self.nfilts))
+ self.analog_sig_source_x_0.set_sampling_freq(self.samp_rate)
+ self.uhd_usrp_source_0.set_samp_rate(self.samp_rate)
+
+ def get_sps(self):
+ return self.sps
+
+ def set_sps(self, sps):
+ self.sps = sps
+ self.set_rrc_taps(firdes.root_raised_cosine(self.nfilts, self.nfilts*self.samp_rate, self.samp_rate/self.sps, self.alpha, 11*self.sps*self.nfilts))
+ self.blocks_moving_average_xx_0.set_length_and_scale(self.sps, 1)
+ self.blocks_moving_average_xx_0_0.set_length_and_scale(self.sps, 1)
+ self.digital_fll_band_edge_cc_0_0.set_loop_bandwidth(2*math.pi/self.sps/100)
+
+ def get_nfilts(self):
+ return self.nfilts
+
+ def set_nfilts(self, nfilts):
+ self.nfilts = nfilts
+ self.set_rrc_taps(firdes.root_raised_cosine(self.nfilts, self.nfilts*self.samp_rate, self.samp_rate/self.sps, self.alpha, 11*self.sps*self.nfilts))
+
+ def get_alpha(self):
+ return self.alpha
+
+ def set_alpha(self, alpha):
+ self.alpha = alpha
+ self.set_rrc_taps(firdes.root_raised_cosine(self.nfilts, self.nfilts*self.samp_rate, self.samp_rate/self.sps, self.alpha, 11*self.sps*self.nfilts))
+
+ def get_rrc_taps(self):
+ return self.rrc_taps
+
+ def set_rrc_taps(self, rrc_taps):
+ self.rrc_taps = rrc_taps
+
+ def get_lbc(self):
+ return self.lbc
+
+ def set_lbc(self, lbc):
+ self.lbc = lbc
+ self.digital_costas_loop_cc_0.set_loop_bandwidth(self.lbc)
+
+ def get_fun_prob(self):
+ return self.fun_prob
+
+ def set_fun_prob(self, fun_prob):
+ self.fun_prob = fun_prob
+ self.analog_const_source_x_0_0.set_offset(self.fun_prob)
+
+def argument_parser():
+ parser = ArgumentParser()
+ parser.add_argument(
+ "--args", dest="args", type=str, default='',
+ help="Set args [default=%(default)r]")
+ parser.add_argument(
+ "--freq", dest="freq", type=eng_float, default="3.32G",
+ help="Set freq [default=%(default)r]")
+ parser.add_argument(
+ "--gainrx", dest="gainrx", type=eng_float, default="30.0",
+ help="Set gainrx [default=%(default)r]")
+ parser.add_argument(
+ "--noise", dest="noise", type=eng_float, default="8.0",
+ help="Set noise [default=%(default)r]")
+ parser.add_argument(
+ "--offset", dest="offset", type=eng_float, default="250.0k",
+ help="Set offset [default=%(default)r]")
+ parser.add_argument(
+ "--samp-rate", dest="samp_rate", type=eng_float, default="2.0M",
+ help="Set samp_rate [default=%(default)r]")
+ parser.add_argument(
+ "--sps", dest="sps", type=intx, default=16,
+ help="Set sps [default=%(default)r]")
+ parser.add_argument(
+ "--uav-id", dest="uav_id", type=int, default=None,
+ help="TDM slot index for this UAV (0-indexed). "
+ "If omitted, read from config/client.yaml.")
+ parser.add_argument(
+ "--num-uavs", dest="num_uavs", type=int, default=None,
+ help="Total number of UAVs (TDM slots). "
+ "If omitted, derived from config/scenario.csv.")
+ parser.add_argument(
+ "--slot-duration", dest="slot_duration", type=float, default=None,
+ help="TDM slot duration in seconds [default: 0.5 or from client.yaml]")
+ parser.add_argument(
+ "--guard-interval", dest="guard_interval", type=float, default=None,
+ help="TDM guard interval in seconds [default: 0.05 or from client.yaml]")
+ return parser
+
+
+def _resolve_tdm_options(options):
+ """Fill in TDM parameters from client.yaml / scenario.csv when not
+ provided on the command line."""
+ import os, yaml
+ cfg_dir = '/root/miSim/aerpaw/config'
+ env_cfg = os.environ.get('AERPAW_CLIENT_CONFIG', '')
+ if env_cfg:
+ yaml_path = env_cfg if os.path.isabs(env_cfg) else os.path.join('/root/miSim/aerpaw', env_cfg)
+ else:
+ yaml_path = os.path.join(cfg_dir, 'client.yaml')
+
+ cfg = {}
+ if os.path.isfile(yaml_path):
+ with open(yaml_path, 'r') as f:
+ cfg = yaml.safe_load(f) or {}
+
+ tdm_cfg = cfg.get('tdm', {})
+
+ if options.uav_id is None:
+ options.uav_id = int(cfg.get('uav_id', 0))
+ if options.slot_duration is None:
+ options.slot_duration = float(tdm_cfg.get('slot_duration', 0.5))
+ if options.guard_interval is None:
+ options.guard_interval = float(tdm_cfg.get('guard_interval', 0.05))
+ if options.num_uavs is None:
+ try:
+ options.num_uavs = derive_num_uavs_from_csv(
+ '/root/miSim/aerpaw/config/scenario.csv')
+ except Exception as e:
+ print(f"[TDM] Warning: could not derive num_uavs from scenario.csv: {e}")
+ print("[TDM] Defaulting to num_uavs=1 (TDM effectively disabled)")
+ options.num_uavs = 1
+
+ return options
+
+
+def main(top_block_cls=CSwSNRRX, options=None):
+ if options is None:
+ options = argument_parser().parse_args()
+
+ options = _resolve_tdm_options(options)
+
+ print(f"[TDM-RX] Config: uav_id={options.uav_id}, "
+ f"num_uavs={options.num_uavs}, slot={options.slot_duration}s, "
+ f"guard={options.guard_interval}s")
+ print(f"[TDM-RX] Receiver runs continuously; measurements from all "
+ f"TX slots interleave into output files.")
+
+ tb = top_block_cls(
+ args=options.args, freq=options.freq, gainrx=options.gainrx,
+ noise=options.noise, offset=options.offset,
+ samp_rate=options.samp_rate, sps=options.sps,
+ uav_id=options.uav_id, num_uavs=options.num_uavs,
+ slot_duration=options.slot_duration,
+ guard_interval=options.guard_interval)
+
+ def sig_handler(sig=None, frame=None):
+ tb.stop()
+ tb.wait()
+ sys.exit(0)
+
+ signal.signal(signal.SIGINT, sig_handler)
+ signal.signal(signal.SIGTERM, sig_handler)
+
+ tb.start()
+
+ try:
+ input('Press Enter to quit: ')
+ except EOFError:
+ pass
+ tb.stop()
+ tb.wait()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/aerpaw/radio/CSwSNRTX.py b/aerpaw/radio/CSwSNRTX.py
new file mode 100644
index 0000000..023460d
--- /dev/null
+++ b/aerpaw/radio/CSwSNRTX.py
@@ -0,0 +1,336 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+
+#
+# SPDX-License-Identifier: GPL-3.0
+#
+# GNU Radio Python Flow Graph
+# Title: CSwSNRTX
+# Author: Ozgur Ozdemir
+# Description: Channel Sounder Transmitter with offset freq
+# GNU Radio version: v3.8.5.0-6-g57bd109d
+
+from gnuradio import analog
+from gnuradio import blocks
+from gnuradio import digital
+from gnuradio import filter
+from gnuradio.filter import firdes
+from gnuradio import gr
+import sys
+import signal
+import threading
+from argparse import ArgumentParser
+from gnuradio.eng_arg import eng_float, intx
+from gnuradio import eng_notation
+from gnuradio import uhd
+import time
+
+
+def derive_num_uavs_from_csv(csv_path=None):
+ """Derive number of UAVs from scenario.csv by counting initial positions.
+
+ The initialPositions column contains a quoted comma-separated list of
+ x,y,z triples. num_uavs = len(values) / 3.
+ """
+ import os, csv
+ if csv_path is None:
+ csv_path = '/root/miSim/aerpaw/config/scenario.csv'
+ with open(csv_path, 'r') as f:
+ reader = csv.reader(f, skipinitialspace=True)
+ header = [h.strip() for h in next(reader)]
+ row = next(reader)
+ col = header.index('initialPositions')
+ init_pos = row[col].strip()
+ n_vals = len([v.strip() for v in init_pos.split(',') if v.strip()])
+ if n_vals % 3 != 0:
+ raise ValueError(f"initialPositions has {n_vals} values; expected a multiple of 3")
+ return n_vals // 3
+
+
+class TdmScheduler(threading.Thread):
+ """Daemon thread that mutes/unmutes a GNU Radio mute_cc block on a
+ wall-clock TDM schedule.
+
+ Slot assignment: current_slot = floor(utc_time / slot_duration) % num_uavs
+ Guard interval: the first *guard_interval* seconds of every slot are
+ always muted to avoid TX overlap due to clock skew.
+ """
+
+ def __init__(self, mute_block, uav_id, num_uavs,
+ slot_duration=0.5, guard_interval=0.05):
+ super().__init__(daemon=True)
+ self.mute_block = mute_block
+ self.uav_id = uav_id
+ self.num_uavs = num_uavs
+ self.slot_duration = slot_duration
+ self.guard_interval = guard_interval
+ self._stop_event = threading.Event()
+
+ def run(self):
+ print(f"[TDM] Scheduler started: uav_id={self.uav_id}, "
+ f"num_uavs={self.num_uavs}, slot={self.slot_duration}s, "
+ f"guard={self.guard_interval}s")
+ while not self._stop_event.is_set():
+ now = time.time()
+ slot_time = now % (self.slot_duration * self.num_uavs)
+ current_slot = int(slot_time / self.slot_duration)
+ time_into_slot = slot_time - current_slot * self.slot_duration
+
+ my_slot = (current_slot == self.uav_id)
+ in_guard = (time_into_slot < self.guard_interval)
+
+ should_mute = (not my_slot) or in_guard
+ self.mute_block.set_mute(should_mute)
+
+ # Sleep ~1 ms for responsive timing without busy-waiting
+ self._stop_event.wait(0.001)
+
+ def stop(self):
+ self._stop_event.set()
+
+
+class CSwSNRTX(gr.top_block):
+
+ def __init__(self, args='', freq=3.32e9, gaintx=76, offset=250e3, samp_rate=2e6, sps=16,
+ uav_id=0, num_uavs=1, slot_duration=0.5, guard_interval=0.05):
+ gr.top_block.__init__(self, "CSwSNRTX")
+
+ ##################################################
+ # Parameters
+ ##################################################
+ self.args = args
+ self.freq = freq
+ self.gaintx = gaintx
+ self.offset = offset
+ self.samp_rate = samp_rate
+ self.sps = sps
+ self.uav_id = uav_id
+ self.num_uavs = num_uavs
+ self.slot_duration = slot_duration
+ self.guard_interval = guard_interval
+
+ ##################################################
+ # Variables
+ ##################################################
+ self.alpha = alpha = 0.99
+
+ ##################################################
+ # Blocks
+ ##################################################
+ self.uhd_usrp_sink_0 = uhd.usrp_sink(
+ ",".join(("", args)),
+ uhd.stream_args(
+ cpu_format="fc32",
+ args='',
+ channels=list(range(0,1)),
+ ),
+ '',
+ )
+ self.uhd_usrp_sink_0.set_center_freq(freq, 0)
+ self.uhd_usrp_sink_0.set_gain(gaintx, 0)
+ self.uhd_usrp_sink_0.set_antenna('TX/RX', 0)
+ self.uhd_usrp_sink_0.set_samp_rate(samp_rate)
+ self.uhd_usrp_sink_0.set_time_unknown_pps(uhd.time_spec())
+ self.root_raised_cosine_filter_0 = filter.fir_filter_ccf(
+ 1,
+ firdes.root_raised_cosine(
+ sps,
+ samp_rate,
+ samp_rate/sps,
+ alpha,
+ 10*sps+1))
+ self.interp_fir_filter_xxx_0 = filter.interp_fir_filter_ccc(sps, [1]+[0]*(sps-1))
+ self.interp_fir_filter_xxx_0.declare_sample_delay(0)
+ self.digital_glfsr_source_x_0 = digital.glfsr_source_b(12, True, 0, 1)
+ self.digital_chunks_to_symbols_xx_0 = digital.chunks_to_symbols_bc((-1,1), 1)
+ self.blocks_multiply_xx_0 = blocks.multiply_vcc(1)
+ self.blocks_multiply_const_vxx_0 = blocks.multiply_const_cc(1/1.58)
+ self.blocks_mute_0 = blocks.mute_cc(True) # TDM: start muted
+ self.analog_sig_source_x_0 = analog.sig_source_c(samp_rate, analog.GR_COS_WAVE, offset, 1, 0, 0)
+
+
+ ##################################################
+ # Connections
+ ##################################################
+ self.connect((self.analog_sig_source_x_0, 0), (self.blocks_multiply_xx_0, 1))
+ self.connect((self.blocks_multiply_const_vxx_0, 0), (self.blocks_mute_0, 0))
+ self.connect((self.blocks_mute_0, 0), (self.uhd_usrp_sink_0, 0))
+ self.connect((self.blocks_multiply_xx_0, 0), (self.blocks_multiply_const_vxx_0, 0))
+ self.connect((self.digital_chunks_to_symbols_xx_0, 0), (self.interp_fir_filter_xxx_0, 0))
+ self.connect((self.digital_glfsr_source_x_0, 0), (self.digital_chunks_to_symbols_xx_0, 0))
+ self.connect((self.interp_fir_filter_xxx_0, 0), (self.root_raised_cosine_filter_0, 0))
+ self.connect((self.root_raised_cosine_filter_0, 0), (self.blocks_multiply_xx_0, 0))
+
+
+ def get_args(self):
+ return self.args
+
+ def set_args(self, args):
+ self.args = args
+
+ def get_freq(self):
+ return self.freq
+
+ def set_freq(self, freq):
+ self.freq = freq
+ self.uhd_usrp_sink_0.set_center_freq(self.freq, 0)
+
+ def get_gaintx(self):
+ return self.gaintx
+
+ def set_gaintx(self, gaintx):
+ self.gaintx = gaintx
+ self.uhd_usrp_sink_0.set_gain(self.gaintx, 0)
+
+ def get_offset(self):
+ return self.offset
+
+ def set_offset(self, offset):
+ self.offset = offset
+ self.analog_sig_source_x_0.set_frequency(self.offset)
+
+ def get_samp_rate(self):
+ return self.samp_rate
+
+ def set_samp_rate(self, samp_rate):
+ self.samp_rate = samp_rate
+ self.analog_sig_source_x_0.set_sampling_freq(self.samp_rate)
+ self.root_raised_cosine_filter_0.set_taps(firdes.root_raised_cosine(self.sps, self.samp_rate, self.samp_rate/self.sps, self.alpha, 10*self.sps+1))
+ self.uhd_usrp_sink_0.set_samp_rate(self.samp_rate)
+
+ def get_sps(self):
+ return self.sps
+
+ def set_sps(self, sps):
+ self.sps = sps
+ self.interp_fir_filter_xxx_0.set_taps([1]+[0]*(self.sps-1))
+ self.root_raised_cosine_filter_0.set_taps(firdes.root_raised_cosine(self.sps, self.samp_rate, self.samp_rate/self.sps, self.alpha, 10*self.sps+1))
+
+ def get_alpha(self):
+ return self.alpha
+
+ def set_alpha(self, alpha):
+ self.alpha = alpha
+ self.root_raised_cosine_filter_0.set_taps(firdes.root_raised_cosine(self.sps, self.samp_rate, self.samp_rate/self.sps, self.alpha, 10*self.sps+1))
+
+
+def argument_parser():
+ description = 'Channel Sounder Transmitter with offset freq'
+ parser = ArgumentParser(description=description)
+ parser.add_argument(
+ "--args", dest="args", type=str, default='',
+ help="Set args [default=%(default)r]")
+ parser.add_argument(
+ "--freq", dest="freq", type=eng_float, default="3.32G",
+ help="Set freq [default=%(default)r]")
+ parser.add_argument(
+ "--gaintx", dest="gaintx", type=eng_float, default="76.0",
+ help="Set gaintx [default=%(default)r]")
+ parser.add_argument(
+ "--offset", dest="offset", type=eng_float, default="250.0k",
+ help="Set offset [default=%(default)r]")
+ parser.add_argument(
+ "--samp-rate", dest="samp_rate", type=eng_float, default="2.0M",
+ help="Set samp_rate [default=%(default)r]")
+ parser.add_argument(
+ "--sps", dest="sps", type=intx, default=16,
+ help="Set sps [default=%(default)r]")
+ parser.add_argument(
+ "--uav-id", dest="uav_id", type=int, default=None,
+ help="TDM slot index for this UAV (0-indexed). "
+ "If omitted, read from config/client.yaml.")
+ parser.add_argument(
+ "--num-uavs", dest="num_uavs", type=int, default=None,
+ help="Total number of UAVs (TDM slots). "
+ "If omitted, derived from config/scenario.csv.")
+ parser.add_argument(
+ "--slot-duration", dest="slot_duration", type=float, default=None,
+ help="TDM slot duration in seconds [default: 0.5 or from client.yaml]")
+ parser.add_argument(
+ "--guard-interval", dest="guard_interval", type=float, default=None,
+ help="TDM guard interval in seconds [default: 0.05 or from client.yaml]")
+ return parser
+
+
+def _resolve_tdm_options(options):
+ """Fill in TDM parameters from client.yaml / scenario.csv when not
+ provided on the command line."""
+ import os, yaml
+ cfg_dir = '/root/miSim/aerpaw/config'
+ env_cfg = os.environ.get('AERPAW_CLIENT_CONFIG', '')
+ if env_cfg:
+ yaml_path = env_cfg if os.path.isabs(env_cfg) else os.path.join('/root/miSim/aerpaw', env_cfg)
+ else:
+ yaml_path = os.path.join(cfg_dir, 'client.yaml')
+
+ cfg = {}
+ if os.path.isfile(yaml_path):
+ with open(yaml_path, 'r') as f:
+ cfg = yaml.safe_load(f) or {}
+
+ tdm_cfg = cfg.get('tdm', {})
+
+ if options.uav_id is None:
+ options.uav_id = int(cfg.get('uav_id', 0))
+ if options.slot_duration is None:
+ options.slot_duration = float(tdm_cfg.get('slot_duration', 0.5))
+ if options.guard_interval is None:
+ options.guard_interval = float(tdm_cfg.get('guard_interval', 0.05))
+ if options.num_uavs is None:
+ try:
+ options.num_uavs = derive_num_uavs_from_csv(
+ '/root/miSim/aerpaw/config/scenario.csv')
+ except Exception as e:
+ print(f"[TDM] Warning: could not derive num_uavs from scenario.csv: {e}")
+ print("[TDM] Defaulting to num_uavs=1 (TDM effectively disabled)")
+ options.num_uavs = 1
+
+ return options
+
+
+def main(top_block_cls=CSwSNRTX, options=None):
+ if options is None:
+ options = argument_parser().parse_args()
+
+ options = _resolve_tdm_options(options)
+
+ tb = top_block_cls(
+ args=options.args, freq=options.freq, gaintx=options.gaintx,
+ offset=options.offset, samp_rate=options.samp_rate, sps=options.sps,
+ uav_id=options.uav_id, num_uavs=options.num_uavs,
+ slot_duration=options.slot_duration,
+ guard_interval=options.guard_interval)
+
+ tdm_sched = TdmScheduler(
+ tb.blocks_mute_0,
+ uav_id=options.uav_id,
+ num_uavs=options.num_uavs,
+ slot_duration=options.slot_duration,
+ guard_interval=options.guard_interval)
+
+ def sig_handler(sig=None, frame=None):
+ tdm_sched.stop()
+ tb.stop()
+ tb.wait()
+ sys.exit(0)
+
+ signal.signal(signal.SIGINT, sig_handler)
+ signal.signal(signal.SIGTERM, sig_handler)
+
+ tb.start()
+ tdm_sched.start()
+
+ try:
+ input('Press Enter to quit: ')
+ except EOFError:
+ pass
+ tdm_sched.stop()
+ tb.stop()
+ tb.wait()
+
+
+if __name__ == '__main__':
+ main()
+(END)
+
+
diff --git a/aerpaw/radio/startchannelsounderRXGRC.sh b/aerpaw/radio/startchannelsounderRXGRC.sh
new file mode 100755
index 0000000..ec7d493
--- /dev/null
+++ b/aerpaw/radio/startchannelsounderRXGRC.sh
@@ -0,0 +1,23 @@
+#!/bin/bash
+GAIN_RX=30
+OFFSET=250e3
+SAMP_RATE=2e6
+SPS=16
+
+# Custom
+RX_FREQ=3.32e9
+
+if [ "$LAUNCH_MODE" == "TESTBED" ]; then
+ #To select a specific device
+ #ARGS="serial=31E74A9"
+ ARGS=NULL
+elif [ "$LAUNCH_MODE" == "EMULATION" ]; then
+ #ARGS='type=zmq'
+ ARGS=NULL
+else
+ echo "Warning: LAUNCH_MODE not set (got '${LAUNCH_MODE}'). Defaulting to TESTBED."
+ ARGS=NULL
+fi
+
+cd $PROFILE_DIR"/SDR_control/Channel_Sounderv3"
+python3 CSwSNRRX.py --freq $RX_FREQ --gainrx $GAIN_RX --noise 0 --args $ARGS --offset $OFFSET --samp-rate $SAMP_RATE --sps $SPS
\ No newline at end of file
diff --git a/aerpaw/radio/startchannelsounderTXGRC.sh b/aerpaw/radio/startchannelsounderTXGRC.sh
new file mode 100755
index 0000000..20fb397
--- /dev/null
+++ b/aerpaw/radio/startchannelsounderTXGRC.sh
@@ -0,0 +1,23 @@
+#!/bin/bash
+GAIN_TX=76
+OFFSET=250e3
+SAMP_RATE=2e6
+SPS=16
+
+# Custom
+TX_FREQ=3.32e9
+
+if [ "$LAUNCH_MODE" == "TESTBED" ]; then
+ #To select a specific device
+ #ARGS="serial=31E74A9"
+ ARGS=NULL
+elif [ "$LAUNCH_MODE" == "EMULATION" ]; then
+ #ARGS='type=zmq'
+ ARGS=NULL
+else
+ echo "Warning: LAUNCH_MODE not set (got '${LAUNCH_MODE}'). Defaulting to TESTBED."
+ ARGS=NULL
+fi
+
+cd $PROFILE_DIR"/SDR_control/Channel_Sounderv3"
+python3 CSwSNRTX.py --freq $TX_FREQ --gaintx $GAIN_TX --args $ARGS --offset $OFFSET --samp-rate $SAMP_RATE --sps $SPS
\ No newline at end of file
diff --git a/aerpaw/radio/updateScripts.sh b/aerpaw/radio/updateScripts.sh
new file mode 100755
index 0000000..52ef5f0
--- /dev/null
+++ b/aerpaw/radio/updateScripts.sh
@@ -0,0 +1,7 @@
+#!/bin/bash
+
+cp startchannelsounderRXGRC.sh /root/Profiles/ProfileScripts/Radio/Helpers/.
+cp startchannelsounderTXGRC.sh /root/Profiles/ProfileScripts/Radio/Helpers/.
+
+cp CSwSNRRX.py /root/Profiles/SDR_control/Channel_Sounderv3/.
+cp CSwSNRTX.py /root/Profiles/SDR_control/Channel_Sounderv3/.
\ No newline at end of file
diff --git a/aerpaw/run_uav.sh b/aerpaw/run_uav.sh
index 62d2275..ee7ef20 100755
--- a/aerpaw/run_uav.sh
+++ b/aerpaw/run_uav.sh
@@ -3,13 +3,13 @@
# Launches UAV client with environment-specific configuration
#
# Usage:
-# ./run_uav.sh local # Use local/simulation configuration
-# ./run_uav.sh testbed # Use AERPAW testbed configuration
+# ./run_uav.sh local # defaults to config/client.yaml
+# ./run_uav.sh testbed config/client2.yaml # use a specific config file
set -e
-# Change to script directory
-cd "$(dirname "$0")"
+# Change to aerpaw directory
+cd /root/miSim/aerpaw
# Activate venv if it exists
if [ -d "venv" ]; then
@@ -23,22 +23,33 @@ elif [ "$1" = "local" ]; then
ENV="local"
else
echo "Error: Environment not specified."
- echo "Usage: $0 [local|testbed]"
+ echo "Usage: $0 [local|testbed] [config_file]"
echo ""
echo " local - Use local/simulation configuration"
echo " testbed - Use AERPAW testbed configuration"
+ echo ""
+ echo " config_file - Path to client YAML (default: config/client.yaml)"
+ exit 1
+fi
+
+# Client config file (optional 2nd argument)
+CONFIG_FILE="${2:-config/client.yaml}"
+if [ ! -f "$CONFIG_FILE" ]; then
+ echo "Error: Config file not found: $CONFIG_FILE"
exit 1
fi
echo "[run_uav] Environment: $ENV"
+echo "[run_uav] Config file: $CONFIG_FILE"
-# Export environment for Python to use
+# Export for Python scripts to use
export AERPAW_ENV="$ENV"
+export AERPAW_CLIENT_CONFIG="$(realpath "$CONFIG_FILE")"
-# Read MAVLink connection from config.yaml using Python
+# Read MAVLink connection from config file using Python
CONN=$(python3 -c "
import yaml
-with open('config/client.yaml') as f:
+with open('$CONFIG_FILE') as f:
cfg = yaml.safe_load(f)
env = cfg['environments']['$ENV']['mavlink']
print(f\"udp:{env['ip']}:{env['port']}\")
diff --git a/resources/project/EEtUlUb-dLAdf0KpMVivaUlztwA/zg8kHdg7qJZOAHkUkvREvBTzyowd.xml b/resources/project/EEtUlUb-dLAdf0KpMVivaUlztwA/zg8kHdg7qJZOAHkUkvREvBTzyowd.xml
new file mode 100644
index 0000000..cc39006
--- /dev/null
+++ b/resources/project/EEtUlUb-dLAdf0KpMVivaUlztwA/zg8kHdg7qJZOAHkUkvREvBTzyowd.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/EEtUlUb-dLAdf0KpMVivaUlztwA/zg8kHdg7qJZOAHkUkvREvBTzyowp.xml b/resources/project/EEtUlUb-dLAdf0KpMVivaUlztwA/zg8kHdg7qJZOAHkUkvREvBTzyowp.xml
new file mode 100644
index 0000000..caa0a58
--- /dev/null
+++ b/resources/project/EEtUlUb-dLAdf0KpMVivaUlztwA/zg8kHdg7qJZOAHkUkvREvBTzyowp.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/gbk0CHypoeHZQfYKLic_g_RhMewd.xml b/resources/project/Gnz6T47dAsmf4YcBHB3EkpeZeYA/l4b98Ty5DTEuIA0u1PkN65-E7z0d.xml
similarity index 100%
rename from resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/gbk0CHypoeHZQfYKLic_g_RhMewd.xml
rename to resources/project/Gnz6T47dAsmf4YcBHB3EkpeZeYA/l4b98Ty5DTEuIA0u1PkN65-E7z0d.xml
diff --git a/resources/project/Gnz6T47dAsmf4YcBHB3EkpeZeYA/l4b98Ty5DTEuIA0u1PkN65-E7z0p.xml b/resources/project/Gnz6T47dAsmf4YcBHB3EkpeZeYA/l4b98Ty5DTEuIA0u1PkN65-E7z0p.xml
new file mode 100644
index 0000000..d3f834c
--- /dev/null
+++ b/resources/project/Gnz6T47dAsmf4YcBHB3EkpeZeYA/l4b98Ty5DTEuIA0u1PkN65-E7z0p.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/2q8QkTf7Be84-j7NLQYQXRr2mh0d.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/2q8QkTf7Be84-j7NLQYQXRr2mh0d.xml
new file mode 100644
index 0000000..4356a6a
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/2q8QkTf7Be84-j7NLQYQXRr2mh0d.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/2q8QkTf7Be84-j7NLQYQXRr2mh0p.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/2q8QkTf7Be84-j7NLQYQXRr2mh0p.xml
new file mode 100644
index 0000000..01cb34e
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/2q8QkTf7Be84-j7NLQYQXRr2mh0p.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/7Qn4v8hXxpt38jHfMvWUU7qISP0d.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/7Qn4v8hXxpt38jHfMvWUU7qISP0d.xml
new file mode 100644
index 0000000..4356a6a
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/7Qn4v8hXxpt38jHfMvWUU7qISP0d.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/7Qn4v8hXxpt38jHfMvWUU7qISP0p.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/7Qn4v8hXxpt38jHfMvWUU7qISP0p.xml
new file mode 100644
index 0000000..f0bbf1c
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/7Qn4v8hXxpt38jHfMvWUU7qISP0p.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CMF2fLjeNlVht3jclP9mYfFr76kd.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CMF2fLjeNlVht3jclP9mYfFr76kd.xml
new file mode 100644
index 0000000..99772b4
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CMF2fLjeNlVht3jclP9mYfFr76kd.xml
@@ -0,0 +1,6 @@
+
+
+
+
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CMF2fLjeNlVht3jclP9mYfFr76kp.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CMF2fLjeNlVht3jclP9mYfFr76kp.xml
new file mode 100644
index 0000000..10059b7
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CMF2fLjeNlVht3jclP9mYfFr76kp.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CnkeWRrKEXdfl5pQ_jhX9KVUx0sd.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CnkeWRrKEXdfl5pQ_jhX9KVUx0sd.xml
new file mode 100644
index 0000000..4356a6a
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CnkeWRrKEXdfl5pQ_jhX9KVUx0sd.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CnkeWRrKEXdfl5pQ_jhX9KVUx0sp.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CnkeWRrKEXdfl5pQ_jhX9KVUx0sp.xml
new file mode 100644
index 0000000..2e1e59c
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/CnkeWRrKEXdfl5pQ_jhX9KVUx0sp.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/fOCCdRscWgypu6LG-RAgt7BPt14d.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/fOCCdRscWgypu6LG-RAgt7BPt14d.xml
new file mode 100644
index 0000000..4356a6a
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/fOCCdRscWgypu6LG-RAgt7BPt14d.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/fOCCdRscWgypu6LG-RAgt7BPt14p.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/fOCCdRscWgypu6LG-RAgt7BPt14p.xml
new file mode 100644
index 0000000..36a8a96
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/fOCCdRscWgypu6LG-RAgt7BPt14p.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/oDJkXIe5Vr4ngmWKGA9D0NvLBfAd.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/oDJkXIe5Vr4ngmWKGA9D0NvLBfAd.xml
new file mode 100644
index 0000000..4356a6a
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/oDJkXIe5Vr4ngmWKGA9D0NvLBfAd.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/oDJkXIe5Vr4ngmWKGA9D0NvLBfAp.xml b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/oDJkXIe5Vr4ngmWKGA9D0NvLBfAp.xml
new file mode 100644
index 0000000..c4e32ba
--- /dev/null
+++ b/resources/project/l4b98Ty5DTEuIA0u1PkN65-E7z0/oDJkXIe5Vr4ngmWKGA9D0NvLBfAp.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/KeON0uDA94030c9sv4Mgl9zKhQEd.xml b/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/KeON0uDA94030c9sv4Mgl9zKhQEd.xml
new file mode 100644
index 0000000..4356a6a
--- /dev/null
+++ b/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/KeON0uDA94030c9sv4Mgl9zKhQEd.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/KeON0uDA94030c9sv4Mgl9zKhQEp.xml b/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/KeON0uDA94030c9sv4Mgl9zKhQEp.xml
new file mode 100644
index 0000000..9f37c61
--- /dev/null
+++ b/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/KeON0uDA94030c9sv4Mgl9zKhQEp.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/eym6FtnTDtwDn4qufwXrm9H2vXod.xml b/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/eym6FtnTDtwDn4qufwXrm9H2vXod.xml
new file mode 100644
index 0000000..4356a6a
--- /dev/null
+++ b/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/eym6FtnTDtwDn4qufwXrm9H2vXod.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/eym6FtnTDtwDn4qufwXrm9H2vXop.xml b/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/eym6FtnTDtwDn4qufwXrm9H2vXop.xml
new file mode 100644
index 0000000..8ec8250
--- /dev/null
+++ b/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/eym6FtnTDtwDn4qufwXrm9H2vXop.xml
@@ -0,0 +1,2 @@
+
+
\ No newline at end of file
diff --git a/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/gbk0CHypoeHZQfYKLic_g_RhMewp.xml b/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/gbk0CHypoeHZQfYKLic_g_RhMewp.xml
deleted file mode 100644
index f8bb87b..0000000
--- a/resources/project/vmVRNnXTZxyEiUtNp09z8POG4ww/gbk0CHypoeHZQfYKLic_g_RhMewp.xml
+++ /dev/null
@@ -1,2 +0,0 @@
-
-
\ No newline at end of file