10 Commits

Author SHA1 Message Date
bdc31ccad5 plot script fixes 2026-03-04 23:06:06 -08:00
d5c7f4f11f finalized plotting utility 2026-03-04 22:32:39 -08:00
110ff87c57 type error fix 2026-03-04 21:27:51 -08:00
51e7533369 added radio plotting tools 2026-03-04 21:22:33 -08:00
3fd4462f11 plotting update 2026-03-04 18:42:17 -08:00
12b6e79f1e fixed GPS log out path 2026-03-04 18:21:39 -08:00
e801018d9c radio experiment TDM working 2026-03-04 17:26:50 -08:00
d5307f63e9 seems to line up well again, constrainMotion updates 2026-03-03 20:14:55 -08:00
ac52e0414d scenario update, quadprog issue 2026-03-03 19:32:13 -08:00
f140b55a63 obstacle respected now 2026-03-03 18:53:19 -08:00
73 changed files with 1557 additions and 235 deletions

View File

@@ -48,13 +48,13 @@ function [obj] = constrainMotion(obj)
% Correction splits between 2 agents, so |A| = 2*r_sum
r_sum_ij = obj.agents{ii}.collisionGeometry.radius + obj.agents{jj}.collisionGeometry.radius;
v_max_ij = max(obj.agents{ii}.initialStepSize, obj.agents{jj}.initialStepSize) / obj.timestep;
slack = -(4 * r_sum_ij * v_max_ij / obj.barrierGain)^(1 / obj.barrierExponent);
hMin = -(4 * r_sum_ij * v_max_ij / obj.barrierGain)^(1 / obj.barrierExponent);
if norm(A(kk, :)) < 1e-9
% Agents are coincident: A-row is zero, so b < 0 would make
% 0 b unsatisfiable. Fall back to b = 0 (no correction possible).
b(kk) = 0;
else
b(kk) = obj.barrierGain * max(slack, h(ii, jj))^obj.barrierExponent;
b(kk) = obj.barrierGain * max(hMin, h(ii, jj))^obj.barrierExponent;
end
kk = kk + 1;
end
@@ -73,8 +73,8 @@ function [obj] = constrainMotion(obj)
% Floor for single-agent constraint: full correction on one agent, |A| = 2*r_i
r_i = obj.agents{ii}.collisionGeometry.radius;
v_max_i = obj.agents{ii}.initialStepSize / obj.timestep;
h_floor_i = -(2 * r_i * v_max_i / obj.barrierGain)^(1 / obj.barrierExponent);
b(kk) = obj.barrierGain * max(h_floor_i, hObs(ii, jj))^obj.barrierExponent;
hMin = -(2 * r_i * v_max_i / obj.barrierGain)^(1 / obj.barrierExponent);
b(kk) = obj.barrierGain * max(hMin, hObs(ii, jj))^obj.barrierExponent;
kk = kk + 1;
end
@@ -157,17 +157,24 @@ function [obj] = constrainMotion(obj)
end
opt = optimoptions("quadprog", "Display", "off", "Algorithm", "active-set", "UseCodegenSolver", true);
x0 = zeros(size(H, 1), 1);
[vNew, ~, exitflag, m] = quadprog(H, double(f), A, b, [], [], [], [], x0, opt);
if coder.target('MATLAB')
assert(exitflag == 1, sprintf("quadprog failure... %s%s", newline, m.message));
end
[vNew, ~, exitflag] = quadprog(H, double(f), A, b, [], [], [], [], x0, opt);
vNew = reshape(vNew, 3, nAgents)';
if exitflag <= 0
if exitflag < 0
% Infeasible or other hard failure: hold all agents at current positions
if coder.target('MATLAB')
warning("QP failed, continuing with unconstrained solution...")
warning("QP infeasible (exitflag=%d), holding positions.", int16(exitflag));
else
fprintf("[constrainMotion] QP infeasible (exitflag=%d), holding positions\n", int16(exitflag));
end
vNew = zeros(nAgents, 3);
elseif exitflag == 0
% Max iterations exceeded: use suboptimal solution already in vNew
if coder.target('MATLAB')
warning("QP max iterations exceeded, using suboptimal solution.");
else
fprintf("[constrainMotion] QP max iterations exceeded, using suboptimal solution\n");
end
vNew = v;
end
% Update the "next position" that was previously set by unconstrained

View File

@@ -19,7 +19,10 @@ classdef miSim
barrierExponent = NaN; % CBF exponent parameter
minAlt = 0; % minimum allowable altitude (m)
artifactName = "";
f; % main plotting tiled layout figure
fPerf; % performance plot figure
% Indicies for various plot types in the main tiled layout figure
spatialPlotIndices = [6, 4, 3, 2];
end
properties (Access = private)
@@ -31,7 +34,6 @@ classdef miSim
% Plot objects
makePlots = true; % enable/disable simulation plotting (performance implications)
makeVideo = true; % enable/disable VideoWriter (performance implications)
f; % main plotting tiled layout figure
connectionsPlot; % objects for lines connecting agents in spatial plots
graphPlot; % objects for abstract network graph plot
partitionPlot; % objects for partition plot
@@ -41,7 +43,6 @@ classdef miSim
trailPlot; % objects for agent trail plot
% Indicies for various plot types in the main tiled layout figure
spatialPlotIndices = [6, 4, 3, 2];
objectivePlotIndices = [6, 4];
networkGraphIndex = 5;
partitionGraphIndex = 1;

View File

@@ -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():
@@ -115,8 +116,9 @@ def _gps_log_row(vehicle, line_num, writer):
async def _gps_log_loop(drone):
"""Background async task that logs GPS data at 1Hz."""
host = platform.node()
filename = f"/root/Results/GPS_DATA_{host}_{datetime.datetime.now().strftime('%Y-%m-%d_%H:%M:%S')}.csv"
results_dir = os.environ.get('RESULTS_DIR', '/root/Results')
log_prefix = os.environ.get('LOG_PREFIX', datetime.datetime.now().strftime('%Y-%m-%d_%H_%M_%S'))
filename = os.path.join(results_dir, f"{log_prefix}_gps_log.csv")
print(f"[UAV] GPS logging to {filename}")
line_num = 1
try:

View File

@@ -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

View File

@@ -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

View File

@@ -1,2 +1,2 @@
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax
5, 100, 30.0, 0.1, 1.0, 2.0, 100, 3, "3.0, 3.0", "30.0, 30.0", "80.0, 80.0", "0.25, 0.25", "5.0, 5.0", "0.1, 0.1", "0.0, 0.0, 0.0", "50.0, 50.0, 80.0", "35.0, 35.0", "10, 5, 5, 10", 0.15, "5.0, 10.0, 45.0, 15.0, 10.0, 35.0", 1, "2.0, 15.0, 0.0", "25.0, 25.0, 50.0"
5, 120, 30.0, 0.1, 1.0, 2.0, 100, 3, "3.0, 3.0", "30.0, 30.0", "80.0, 80.0", "0.25, 0.25", "5.0, 5.0", "0.1, 0.1", "0.0, 0.0, 0.0", "50.0, 50.0, 80.0", "35.0, 35.0", "10, 5, 5, 10", 0.15, "5.0, 10.0, 45.0, 15.0, 10.0, 35.0", 1, "2.0, 15.0, 0.0", "25.0, 25.0, 50.0"
1 timestep maxIter minAlt discretizationStep protectedRange initialStepSize barrierGain barrierExponent collisionRadius comRange alphaDist betaDist alphaTilt betaTilt domainMin domainMax objectivePos objectiveVar sensorPerformanceMinimum initialPositions numObstacles obstacleMin obstacleMax
2 5 100 120 30.0 0.1 1.0 2.0 100 3 3.0, 3.0 30.0, 30.0 80.0, 80.0 0.25, 0.25 5.0, 5.0 0.1, 0.1 0.0, 0.0, 0.0 50.0, 50.0, 80.0 35.0, 35.0 10, 5, 5, 10 0.15 5.0, 10.0, 45.0, 15.0, 10.0, 35.0 1 2.0, 15.0, 0.0 25.0, 25.0, 50.0

View File

@@ -128,6 +128,11 @@
<Size type="coderapp.internal.codertype.Dimension"/>
<Size type="coderapp.internal.codertype.Dimension"/>
</Types>
<Types id="26" type="coderapp.internal.codertype.PrimitiveType">
<ClassName>int32</ClassName>
<Size type="coderapp.internal.codertype.Dimension"/>
<Size type="coderapp.internal.codertype.Dimension"/>
</Types>
</Types>
</coderapp.internal.interface.project.Interface>
</MF0>
@@ -519,575 +524,569 @@
</Artifacts>
<Artifacts id="65" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/factoryConstruct.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/feasibleX0ForWorkingSet.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="66" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/factoryConstruct.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/feasibleX0ForWorkingSet.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="67" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/feasibleX0ForWorkingSet.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/feasibleratiotest.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="68" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/feasibleX0ForWorkingSet.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/feasibleratiotest.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="69" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/feasibleratiotest.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/find.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="70" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/feasibleratiotest.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/find.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="71" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/find.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/fullColLDL2_.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="72" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/find.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/fullColLDL2_.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="73" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/fullColLDL2_.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/guidance_step.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="74" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/fullColLDL2_.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/guidance_step.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="75" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/guidance_step.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/iterate.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="76" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/guidance_step.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/iterate.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="77" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/iterate.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ixamax.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="78" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/iterate.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ixamax.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="79" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ixamax.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ixfun.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="80" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ixamax.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ixfun.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="81" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ixfun.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/lesserNeighbor.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="82" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ixfun.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/lesserNeighbor.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="83" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/lesserNeighbor.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/linearForm_.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="84" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/lesserNeighbor.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/linearForm_.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="85" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/linearForm_.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/maxConstraintViolation.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="86" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/linearForm_.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/maxConstraintViolation.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="87" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/maxConstraintViolation.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/meshgrid.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="88" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/maxConstraintViolation.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/meshgrid.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="89" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/meshgrid.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/miSim.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="90" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/meshgrid.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/miSim.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="91" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/miSim.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/minOrMax.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="92" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/miSim.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/minOrMax.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="93" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/minOrMax.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/mpower.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="94" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/minOrMax.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/mpower.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="95" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/mpower.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/nchoosek.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="96" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/mpower.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/nchoosek.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="97" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/nchoosek.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/norm.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="98" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/nchoosek.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/norm.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="99" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/norm.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/partition.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="100" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/norm.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/partition.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="101" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/partition.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/phaseone.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="102" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/partition.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/phaseone.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="103" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/phaseone.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/quadprog.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="104" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/phaseone.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/quadprog.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="105" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/quadprog.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ratiotest.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="106" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/quadprog.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ratiotest.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="107" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ratiotest.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rectangularPrism.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="108" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ratiotest.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/removeConstr.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="109" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rectangularPrism.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/removeConstr.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="110" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/removeConstr.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/repmat.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="111" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/removeConstr.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/repmat.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="112" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/repmat.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rtGetInf.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="113" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/repmat.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rtGetInf.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="114" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rtGetInf.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rtGetNaN.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="115" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rtGetInf.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rtGetNaN.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="116" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rtGetNaN.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rt_defines.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="117" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rtGetNaN.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rt_nonfinite.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="118" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rt_defines.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rt_nonfinite.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="119" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rt_nonfinite.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rtwtypes.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="120" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rt_nonfinite.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/run.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="121" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rtwtypes.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/run.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="122" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/run.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sensingObjective.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="123" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/run.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sensingObjective.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="124" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sensingObjective.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sensorPerformance.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="125" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sensorPerformance.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sensorPerformance.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="126" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sensorPerformance.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/setProblemType.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="127" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/setProblemType.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/setProblemType.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="128" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/setProblemType.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sigmoidSensor.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="129" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sigmoidSensor.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sort.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="130" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sort.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sort.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="131" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sort.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/spherical.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="132" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/spherical.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sprintf.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="133" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sprintf.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sprintf.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="134" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sprintf.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/squareQ_appendCol.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="135" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/squareQ_appendCol.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/squareQ_appendCol.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="136" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/squareQ_appendCol.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/string1.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="137" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/string1.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sum.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="138" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sum.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sum.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="139" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sum.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/unique.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="140" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/unique.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/unique.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="141" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/unique.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/vecnorm.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="142" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/vecnorm.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/vecnorm.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="143" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/vecnorm.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xgemv.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="144" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xgemv.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xgemv.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="145" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xgemv.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xgeqp3.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="146" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xgeqp3.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xgeqp3.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="147" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xgeqp3.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xnrm2.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="148" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xnrm2.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xnrm2.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="149" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xnrm2.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xrotg.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="150" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xrotg.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xrotg.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="151" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xrotg.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzgeqp3.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="152" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzgeqp3.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzgeqp3.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="153" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzgeqp3.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarf.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="154" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarf.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarf.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="155" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarf.h</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarfg.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="156" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarfg.cpp</Path>
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarfg.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="157" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarfg.h</Path>
<Path>/home/kdee/matlab/R2025a/extern/include/tmwtypes.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="158" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/matlab/R2025a/extern/include/tmwtypes.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="159" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/examples/main.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="160" type="coderapp.internal.build.mfz.CodegenArtifact">
<Artifacts id="159" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/examples/main.h</Path>
</File>
@@ -1095,7 +1094,7 @@
</Artifacts>
<BuildFolder type="coderapp.internal.util.mfz.FileSpec"/>
<Success>true</Success>
<Timestamp>2026-03-03T15:54:20</Timestamp>
<Timestamp>2026-03-03T19:58:03</Timestamp>
</MainBuildResult>
</coderapp.internal.mlc.mfz.MatlabCoderProjectState>
</MF0>

View File

@@ -135,7 +135,7 @@ if isInit
% --- Build obstacle list from flat arrays ---
coder.varsize('obstacleList', [8, 1], [1, 0]);
obstacleList = cell(int32(0), 1);
obstacleList = repmat({rectangularPrism}, numObstacles, 1);
for ii = 1:numObstacles
obs = rectangularPrism;
obs = obs.initialize([obstacleMin(ii, :); obstacleMax(ii, :)], ...

529
aerpaw/radio/CSwSNRRX.py Normal file

File diff suppressed because one or more lines are too long

336
aerpaw/radio/CSwSNRTX.py Normal file
View File

@@ -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)

View File

@@ -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

View File

@@ -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

7
aerpaw/radio/updateScripts.sh Executable file
View File

@@ -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/.

View File

@@ -1,68 +0,0 @@
% Plot setup
f = uifigure;
gf = geoglobe(f);
hold(gf, "on");
c = ["g", "b", "m", "c"]; % plotting colors
% paths
scenarioCsv = fullfile("aerpaw", "config", "scenario.csv");
% configured data
params = readScenarioCsv(scenarioCsv);
% coordinate system constants
seaToGroundLevel = 110; % meters, measured approximately from USGS national map viewer
fID = fopen(fullfile("aerpaw", "config", "client.yaml"), 'r');
yaml = fscanf(fID, '%s');
fclose(fID);
% origin (LLA)
lla0 = [str2double(yaml((strfind(yaml, 'lat:') + 4):(strfind(yaml, 'lon:') - 1))), str2double(yaml((strfind(yaml, 'lon:') + 4):(strfind(yaml, 'alt:') - 1))), seaToGroundLevel];
% Paths to logs
gpsCsvs = dir(fullfile("sandbox", "test10", "*.csv"));
G = cell(size(gpsCsvs));
for ii = 1:size(gpsCsvs, 1)
% Read CSV
G{ii} = readGpsCsv(fullfile(gpsCsvs(ii).folder, gpsCsvs(ii).name));
% Find when algorithm begins/ends (using ENU altitude rate change)
enuTraj = lla2enu([G{ii}.Latitude, G{ii}.Longitude, G{ii}.Altitude], lla0, 'flat');
verticalSpeed = movmean(abs(diff(G{ii}.Altitude)), [10, 0]);
% Automatically detect start/stop of algorithm flight (ignore takeoff, setup, return to liftoff, landing segments of flight)
pctThreshold = 60; % pctThreshold may need adjusting depending on your flight
startIdx = find(verticalSpeed <= prctile(verticalSpeed, pctThreshold), 1, 'first');
stopIdx = find(verticalSpeed <= prctile(verticalSpeed, pctThreshold), 1, 'last');
% % Plot whole flight, including setup/cleanup
startIdx = 1;
stopIdx = length(verticalSpeed);
% Plot recorded trajectory over specified range of indices
geoplot3(gf, G{ii}.Latitude(startIdx:stopIdx), G{ii}.Longitude(startIdx:stopIdx), G{ii}.Altitude(startIdx:stopIdx) + seaToGroundLevel, c(mod(ii, length(c))), 'LineWidth', 2, "MarkerSize", 5);
end
% Plot domain
altOffset = 1; % to avoid clipping into the ground when displayed
domain = [lla0; enu2lla(params.domainMax, lla0, 'flat')];
geoplot3(gf, [domain(1, 1), domain(2, 1), domain(2, 1), domain(1, 1), domain(1, 1)], [domain(1, 2), domain(1, 2), domain(2, 2), domain(2, 2), domain(1, 2)], repmat(domain(1, 3) + altOffset, 1, 5), 'LineWidth', 3, 'Color', 'k');
geoplot3(gf, [domain(1, 1), domain(2, 1), domain(2, 1), domain(1, 1), domain(1, 1)], [domain(1, 2), domain(1, 2), domain(2, 2), domain(2, 2), domain(1, 2)], repmat(domain(2, 3) + altOffset, 1, 5), 'LineWidth', 3, 'Color', 'k');
geoplot3(gf, [domain(1, 1), domain(1, 1)], [domain(1, 2), domain(1, 2)], domain(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'k');
geoplot3(gf, [domain(2, 1), domain(2, 1)], [domain(1, 2), domain(1, 2)], domain(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'k');
geoplot3(gf, [domain(1, 1), domain(1, 1)], [domain(2, 2), domain(2, 2)], domain(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'k');
geoplot3(gf, [domain(2, 1), domain(2, 1)], [domain(2, 2), domain(2, 2)], domain(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'k');
% Plot floor (minimum altitude constraint)
floorAlt = params.minAlt;
geoplot3(gf, [domain(1, 1), domain(2, 1), domain(2, 1), domain(1, 1), domain(1, 1)], [domain(1, 2), domain(1, 2), domain(2, 2), domain(2, 2), domain(1, 2)], repmat(domain(1, 3) + altOffset + floorAlt, 1, 5), 'LineWidth', 3, 'Color', 'r');
% Plot objective
objectivePos = [params.objectivePos, 0];
llaObj = enu2lla(objectivePos, lla0, 'flat');
geoplot3(gf, [llaObj(1), llaObj(1)], [llaObj(2), llaObj(2)], [llaObj(3), domain(2, 3)], 'LineWidth', 3, "Color", 'y');
% finish
hold(gf, "off");

View File

@@ -0,0 +1,97 @@
function [f, G] = plotGpsLogs(logDirs, seaToGroundLevel)
arguments (Input)
logDirs (1, 1) string;
seaToGroundLevel (1, 1) double = 110; % measured approximately from USGS national map viewer for the AERPAW test field
end
arguments (Output)
f (1, 1) matlab.ui.Figure;
G cell;
end
% Plot setup
f = uifigure;
gf = geoglobe(f);
hold(gf, "on");
c = ["g", "b", "m", "c"]; % plotting colors
% paths
scenarioCsv = fullfile(matlab.project.rootProject().RootFolder, "aerpaw", "config", "scenario.csv");
% configured data
params = readScenarioCsv(scenarioCsv);
fID = fopen(fullfile(matlab.project.rootProject().RootFolder, "aerpaw", "config", "client1.yaml"), 'r');
yaml = fscanf(fID, '%s');
fclose(fID);
% origin (LLA)
lla0 = [str2double(yaml((strfind(yaml, 'lat:') + 4):(strfind(yaml, 'lon:') - 1))), str2double(yaml((strfind(yaml, 'lon:') + 4):(strfind(yaml, 'alt:') - 1))), seaToGroundLevel];
logDirs = dir(logDirs);
logDirs = logDirs(3:end);
logDirs = logDirs([logDirs.isdir] == 1);
G = cell(size(logDirs));
for ii = 1:size(logDirs, 1)
% Find GPS log CSV
gpsCsv = dir(fullfile(logDirs(ii).folder, logDirs(ii).name));
gpsCsv = gpsCsv(endsWith({gpsCsv(:).name}, "_gps_log.csv"));
gpsCsv = fullfile(gpsCsv.folder, gpsCsv.name);
% Read GPS log CSV
G{ii} = readGpsLogs(gpsCsv);
% Find when algorithm begins/ends (using ENU altitude rate change)
verticalSpeed = movmean(abs(diff(G{ii}.Altitude)), [10, 0]);
% Automatically detect start/stop of algorithm flight (ignore takeoff, setup, return to liftoff, landing segments of flight)
pctThreshold = 60; % pctThreshold may need adjusting depending on your flight
startIdx = find(verticalSpeed <= prctile(verticalSpeed, pctThreshold), 1, "first");
stopIdx = find(verticalSpeed <= prctile(verticalSpeed, pctThreshold), 1, "last");
% % Plot whole flight, including setup/cleanup
% startIdx = 1;
% stopIdx = length(verticalSpeed);
% Convert LLA trajectory data to ENU for external analysis
% NaN out entries outside the algorithm flight range so they don't plot
enu = NaN(height(G{ii}), 3);
enu(startIdx:stopIdx, :) = lla2enu([G{ii}.Latitude(startIdx:stopIdx), G{ii}.Longitude(startIdx:stopIdx), G{ii}.Altitude(startIdx:stopIdx)], lla0, "flat");
enu = array2table(enu, 'VariableNames', ["East", "North", "Up"]);
G{ii} = [G{ii}, enu];
% Plot recorded trajectory over specified range of indices
geoplot3(gf, G{ii}.Latitude(startIdx:stopIdx), G{ii}.Longitude(startIdx:stopIdx), G{ii}.Altitude(startIdx:stopIdx) + seaToGroundLevel, c(mod(ii, length(c))), 'LineWidth', 2, "MarkerSize", 5);
end
% Plot domain
altOffset = 1; % to avoid clipping into the ground when displayed
domain = [lla0; enu2lla(params.domainMax, lla0, "flat")];
geoplot3(gf, [domain(1, 1), domain(2, 1), domain(2, 1), domain(1, 1), domain(1, 1)], [domain(1, 2), domain(1, 2), domain(2, 2), domain(2, 2), domain(1, 2)], repmat(domain(1, 3) + altOffset, 1, 5), 'LineWidth', 3, 'Color', 'k');
geoplot3(gf, [domain(1, 1), domain(2, 1), domain(2, 1), domain(1, 1), domain(1, 1)], [domain(1, 2), domain(1, 2), domain(2, 2), domain(2, 2), domain(1, 2)], repmat(domain(2, 3) + altOffset, 1, 5), 'LineWidth', 3, 'Color', 'k');
geoplot3(gf, [domain(1, 1), domain(1, 1)], [domain(1, 2), domain(1, 2)], domain(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'k');
geoplot3(gf, [domain(2, 1), domain(2, 1)], [domain(1, 2), domain(1, 2)], domain(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'k');
geoplot3(gf, [domain(1, 1), domain(1, 1)], [domain(2, 2), domain(2, 2)], domain(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'k');
geoplot3(gf, [domain(2, 1), domain(2, 1)], [domain(2, 2), domain(2, 2)], domain(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'k');
% Plot floor (minimum altitude constraint)
floorAlt = params.minAlt;
geoplot3(gf, [domain(1, 1), domain(2, 1), domain(2, 1), domain(1, 1), domain(1, 1)], [domain(1, 2), domain(1, 2), domain(2, 2), domain(2, 2), domain(1, 2)], repmat(domain(1, 3) + altOffset + floorAlt, 1, 5), 'LineWidth', 3, 'Color', 'r');
% Plot objective
objectivePos = [params.objectivePos, 0];
llaObj = enu2lla(objectivePos, lla0, "flat");
geoplot3(gf, [llaObj(1), llaObj(1)], [llaObj(2), llaObj(2)], [llaObj(3), domain(2, 3)], 'LineWidth', 3, "Color", 'y');
% Plot obstacles
for ii = 1:params.numObstacles
obstacle = enu2lla([params.obstacleMin((1 + (ii - 1) * 3):(ii * 3)); params.obstacleMax((1 + (ii - 1) * 3):(ii * 3))], lla0, "flat");
geoplot3(gf, [obstacle(1, 1), obstacle(2, 1), obstacle(2, 1), obstacle(1, 1), obstacle(1, 1)], [obstacle(1, 2), obstacle(1, 2), obstacle(2, 2), obstacle(2, 2), obstacle(1, 2)], repmat(obstacle(1, 3) + altOffset, 1, 5), 'LineWidth', 3, 'Color', 'r');
geoplot3(gf, [obstacle(1, 1), obstacle(2, 1), obstacle(2, 1), obstacle(1, 1), obstacle(1, 1)], [obstacle(1, 2), obstacle(1, 2), obstacle(2, 2), obstacle(2, 2), obstacle(1, 2)], repmat(obstacle(2, 3) + altOffset, 1, 5), 'LineWidth', 3, 'Color', 'r');
geoplot3(gf, [obstacle(1, 1), obstacle(1, 1)], [obstacle(1, 2), obstacle(1, 2)], obstacle(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'r');
geoplot3(gf, [obstacle(2, 1), obstacle(2, 1)], [obstacle(1, 2), obstacle(1, 2)], obstacle(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'r');
geoplot3(gf, [obstacle(1, 1), obstacle(1, 1)], [obstacle(2, 2), obstacle(2, 2)], obstacle(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'r');
geoplot3(gf, [obstacle(2, 1), obstacle(2, 1)], [obstacle(2, 2), obstacle(2, 2)], obstacle(:, 3) + altOffset, 'LineWidth', 3, 'Color', 'r');
end
% finish
hold(gf, "off");
end

View File

@@ -0,0 +1,75 @@
function [f, R] = plotRadioLogs(resultsPath)
arguments (Input)
resultsPath (1, 1) string;
end
arguments (Output)
f (1, 1) matlab.ui.Figure;
R cell;
end
logDirs = dir(resultsPath);
logDirs = logDirs(3:end);
logDirs = logDirs([logDirs.isdir] == 1);
R = cell(size(logDirs));
for ii = 1:size(logDirs, 1)
R{ii} = readRadioLogs(fullfile(logDirs(ii).folder, logDirs(ii).name));
end
% Discard rows where any non-NaN dB metric is below -200 (sentinel values)
for ii = 1:numel(R)
snr = R{ii}.SNR;
pwr = R{ii}.Power;
bad = (snr < -200 & ~isnan(snr)) | (pwr < -200 & ~isnan(pwr));
R{ii}(bad, :) = [];
end
% Build legend labels and color map for up to 4 UAVs
nUAV = numel(R);
colors = lines(nUAV * nUAV);
styles = ["-o", "-s", "-^", "-d", "-v", "-p", "-h", "-<", "->", "-+", "-x", "-*"];
metricNames = ["SNR", "Power", "Quality"];
yLabels = ["SNR (dB)", "Power (dB)", "Quality"];
f = figure;
tl = tiledlayout(3, 1, 'TileSpacing', 'compact', 'Padding', 'compact');
for mi = 1:numel(metricNames)
ax = nexttile(tl);
hold(ax, 'on');
grid(ax, 'on');
legendEntries = string.empty;
ci = 1;
for rxIdx = 1:nUAV
tbl = R{rxIdx};
txIDs = unique(tbl.TxUAVID);
for ti = 1:numel(txIDs)
txID = txIDs(ti);
rows = tbl(tbl.TxUAVID == txID, :);
vals = rows.(metricNames(mi));
% Skip if all NaN for this metric
if all(isnan(vals))
continue;
end
si = mod(ci - 1, numel(styles)) + 1;
plot(ax, rows.Timestamp, vals, styles(si), ...
'Color', colors(ci, :), 'MarkerSize', 3, 'LineWidth', 1);
legendEntries(end+1) = sprintf("TX %d → RX %d", txID, tbl.RxUAVID(1)); %#ok<AGROW>
ci = ci + 1;
end
end
ylabel(ax, yLabels(mi));
if mi == numel(metricNames)
xlabel(ax, 'Time');
end
legend(ax, legendEntries, 'Location', 'best');
hold(ax, 'off');
end
title(tl, 'Radio Channel Metrics');
end

View File

@@ -1,33 +0,0 @@
function [G] = readGpsCsv(csvPath)
arguments (Input)
csvPath (1, 1) string {isfile(csvPath)};
end
arguments (Output)
G (:, 10) table;
end
G = readtable(csvPath, "ReadVariableNames", false);
% first column is just index, meaningless, toss it
G = G(:, 2:end);
% switch to the correct LLA convention (lat, lon, alt)
tmp = G(:, 2);
G(:, 2) = G(:, 1);
G(:, 1) = tmp;
% Split pitch, yaw, roll data read in as one string per timestep into separate columns
PYR = cell2mat(cellfun(@(x) str2num(strip(strip(x, "left", "("), "right", ")")), table2cell(G(:, 5)), "UniformOutput", false)); %#ok<ST2NM>
% Reinsert to original table
G = [G(:, 1:3), table(PYR(:, 1), VariableNames="Pitch"), table(PYR(:, 2), VariableNames="Yaw"), table(PYR(:, 3), VariableNames="Roll"), G(:, 6:end)];
% Clean up datetime entry
G = [table(datetime(G{:,8}, "InputFormat","yyyy-MM-dd HH:mm:ss.SSS", "TimeZone","America/New_York")), G(:, [1:7, 9:10])];
% Fix variable names
G.Properties.VariableNames = ["Timestamp", "Latitude", "Longitude", "Altitude", "Pitch", "Yaw", "Roll", "Voltage", "GPS Status", "Satellites"];
G.Properties.VariableTypes = ["datetime", "double", "double", "double", "double", "double", "double", "double", "double", "double"];
G.Properties.VariableUnits = ["yyyy-MM-dd HH:mm:ss.SSS (UTC+5)", "deg", "deg", "m", "deg", "deg", "deg", "Volts", "", ""];
end

View File

@@ -0,0 +1,32 @@
function [G] = readGpsLogs(logPath)
arguments (Input)
logPath (1, 1) string {isfile(logPath)};
end
arguments (Output)
G (:, 10) table;
end
G = readtable(logPath, "ReadVariableNames", false);
% first column is just index, meaningless, toss it
G = G(:, 2:end);
% switch to the correct LLA convention (lat, lon, alt)
tmp = G(:, 2);
G(:, 2) = G(:, 1);
G(:, 1) = tmp;
% Split pitch, yaw, roll data read in as one string per timestep into separate columns
PYR = cell2mat(cellfun(@(x) str2num(strip(strip(x, "left", "("), "right", ")")), table2cell(G(:, 5)), "UniformOutput", false)); %#ok<ST2NM>
% Reinsert to original table
G = [G(:, 1:3), table(PYR(:, 1), VariableNames="Pitch"), table(PYR(:, 2), VariableNames="Yaw"), table(PYR(:, 3), VariableNames="Roll"), G(:, 6:end)];
% Clean up datetime entry
G = [table(datetime(G{:,8}, "InputFormat","yyyy-MM-dd HH:mm:ss.SSS", "TimeZone","America/New_York")), G(:, [1:7, 9:10])];
% Fix variable names
G.Properties.VariableNames = ["Timestamp", "Latitude", "Longitude", "Altitude", "Pitch", "Yaw", "Roll", "Voltage", "GPS Status", "Satellites"];
G.Properties.VariableTypes = ["datetime", "double", "double", "double", "double", "double", "double", "double", "double", "double"];
G.Properties.VariableUnits = ["yyyy-MM-dd HH:mm:ss.SSS (UTC+5)", "deg", "deg", "m", "deg", "deg", "deg", "Volts", "", ""];
end

View File

@@ -0,0 +1,65 @@
function R = readRadioLogs(logPath)
arguments (Input)
logPath (1, 1) string {isfolder(logPath)};
end
arguments (Output)
R (:, 6) table;
end
% Extract receiving UAV ID from directory name (e.g. "uav0_..." 0)
[~, dirName] = fileparts(logPath);
rxID = int32(sscanf(dirName, 'uav%d'));
metrics = ["quality", "snr", "power"];
logs = dir(logPath);
logs = logs(endsWith({logs(:).name}, metrics + "_log.txt"));
R = table(datetime.empty(0,1), zeros(0,1,'int32'), zeros(0,1,'int32'), zeros(0,1), zeros(0,1), zeros(0,1), ...
'VariableNames', ["Timestamp", "TxUAVID", "RxUAVID", "SNR", "Power", "Quality"]);
for ii = 1:numel(logs)
filepath = fullfile(logs(ii).folder, logs(ii).name);
% Determine which metric this file contains
metric = "";
for m = 1:numel(metrics)
if endsWith(logs(ii).name, metrics(m) + "_log.txt")
metric = metrics(m);
break;
end
end
fid = fopen(filepath, 'r');
% Skip 3 lines: 2 junk (tail errors) + 1 header (tx_uav_id,value)
for k = 1:3
fgetl(fid);
end
data = textscan(fid, '[%26c] %d,%f');
fclose(fid);
ts = datetime(data{1}, 'InputFormat', 'yyyy-MM-dd HH:mm:ss.SSSSSS');
txId = int32(data{2});
val = data{3};
n = numel(ts);
t = table(ts, txId, repmat(rxID, n, 1), NaN(n,1), NaN(n,1), NaN(n,1), ...
'VariableNames', ["Timestamp", "TxUAVID", "RxUAVID", "SNR", "Power", "Quality"]);
switch metric
case "snr", t.SNR = val;
case "power", t.Power = val;
case "quality", t.Quality = val;
end
R = [R; t]; %#ok<AGROW>
end
R = sortrows(R, "Timestamp");
% Remove rows during defined guard period between TDM shifts
R(R.TxUAVID == -1, :) = [];
% Remove self-reception rows (TX == RX)
R(R.TxUAVID == R.RxUAVID, :) = [];
end

View File

@@ -0,0 +1,68 @@
%% Plot AERPAW logs (trajectory, radio)
resultsPath = fullfile(matlab.project.rootProject().RootFolder, "sandbox", "t1"); % Define path to results copied from AERPAW platform
% Plot GPS logged data and scenario information (domain, objective, obstacles)
seaToGroundLevel = 110; % measured approximately from USGS national map viewer
[fGlobe, G] = plotGpsLogs(resultsPath, seaToGroundLevel);
% Plot radio statistics
[fRadio, R] = plotRadioLogs(resultsPath);
%% Run simulation
% Run miSim using same AERPAW scenario definition CSV
csvPath = fullfile(matlab.project.rootProject().RootFolder, "aerpaw", "config", "scenario.csv");
params = readScenarioCsv(csvPath);
% Visualization settings
plotCommsGeometry = false;
makePlots = true;
makeVideo = true;
% Define scenario according to CSV specification
domain = rectangularPrism;
domain = domain.initialize([params.domainMin; params.domainMax], REGION_TYPE.DOMAIN, "Domain");
domain.objective = domain.objective.initialize(objectiveFunctionWrapper(params.objectivePos, reshape(params.objectiveVar, [2 2])), domain, params.discretizationStep, params.protectedRange, params.sensorPerformanceMinimum);
agents = cell(size(params.initialPositions, 2) / 3, 1);
for ii = 1:size(agents, 1)
agents{ii} = agent;
sensorModel = sigmoidSensor;
sensorModel = sensorModel.initialize(params.alphaDist(ii), params.betaDist(ii), params.alphaTilt(ii), params.betaTilt(ii));
collisionGeometry = spherical;
collisionGeometry = collisionGeometry.initialize(params.initialPositions((((ii - 1) * 3) + 1):(ii * 3)), params.collisionRadius(ii), REGION_TYPE.COLLISION, sprintf("Agent %d collision geometry", ii));
agents{ii} = agents{ii}.initialize(params.initialPositions((((ii - 1) * 3) + 1):(ii * 3)), collisionGeometry, sensorModel, params.comRange(ii), params.maxIter, params.initialStepSize, sprintf("Agent %d", ii), plotCommsGeometry);
end
% Create obstacles
obstacles = cell(params.numObstacles, 1);
for ii = 1:size(obstacles, 1)
obstacles{ii} = rectangularPrism;
obstacles{ii} = obstacles{ii}.initialize([params.obstacleMin((((ii - 1) * 3) + 1):(ii * 3)); params.obstacleMax((((ii - 1) * 3) + 1):(ii * 3))], "OBSTACLE", sprintf("Obstacle %d", ii));
end
% Set up simulation
sim = miSim;
sim = sim.initialize(domain, agents, params.barrierGain, params.barrierExponent, params.minAlt, params.timestep, params.maxIter, obstacles, makePlots, makeVideo);
% Save simulation parameters to output file
sim.writeInits();
% Run
sim = sim.run();
%% Plot AERPAW trajectory logs onto simulated result for comparison
% Duplicate plot to overlay with logged trajectories
comparison = figure;
copyobj(sim.f.Children, comparison);
% Plot trajectories on top
for ii = 1:size(G, 1)
for jj = 1:size(sim.spatialPlotIndices, 2)
hold(comparison.Children.Children(sim.spatialPlotIndices(jj)), "on");
plot3(comparison.Children(1).Children(sim.spatialPlotIndices(jj)), G{ii}.East, G{ii}.North, G{ii}.Up + seaToGroundLevel, 'Color', 'r', 'LineWidth', 1);
hold(comparison.Children.Children(sim.spatialPlotIndices(jj)), "off");
end
end

View File

@@ -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']}\")

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="1" type="DIR_SIGNIFIER"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info Ref="aerpaw/radio" Type="Relative"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="df3a85ba-fb12-4318-81b9-0233555f7fe7" type="Reference"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="radio" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="1" type="DIR_SIGNIFIER"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="1" type="DIR_SIGNIFIER"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="plotGpsLogs.m" type="File"/>

View File

@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="plotGpsCsvs.m" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="readRadioLogs.m" type="File"/>

View File

@@ -0,0 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info>
<Category UUID="FileClassCategory">
<Label UUID="design"/>
</Category>
</Info>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="readGpsLogs.m" type="File"/>

View File

@@ -0,0 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info>
<Category UUID="FileClassCategory">
<Label UUID="design"/>
</Category>
</Info>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="plotRadioLogs.m" type="File"/>

View File

@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="readGpsCsv.m" type="File"/>

View File

@@ -0,0 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info>
<Category UUID="FileClassCategory">
<Label UUID="design"/>
</Category>
</Info>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="resultsAnalysis.m" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="1" type="DIR_SIGNIFIER"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="startchannelsounderTXGRC.sh" type="File"/>

View File

@@ -0,0 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info>
<Category UUID="FileClassCategory">
<Label UUID="design"/>
</Category>
</Info>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="startchannelsounderRXGRC.sh" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="CSwSNRTX.py" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="CSwSNRRX.py" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="updateScripts.sh" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="test13" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="t1" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="test14" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="test12" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="t1.zip" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="client1.yaml" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="client2.yaml" type="File"/>

View File

@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="client.yaml" type="File"/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info/>

View File

@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="1" type="DIR_SIGNIFIER"/>

BIN
t1.zip Normal file

Binary file not shown.