Merge branch 'main' into AERPAW-experiments

This commit is contained in:
2026-05-25 15:10:12 -07:00
committed by GitHub
76 changed files with 1690 additions and 205 deletions
+1 -1
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, useDoubleIntegrator, dampingCoeff, useFixedTopology
1, 80, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 50.0", "0.25, 1.0", "8.0, 25.0", "0.1, 0.02", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "60.0, 80.0, 45.0, 70.0", "70, 15, 15, 20, 20, 15, 15, 70", 0.15, "15.0, 15.0, 50.0, 40.0, 10.0, 45.0", 8, "0.0, 30.0, 0.0, 42.0, 30.0, 0.0, 84.0, 30.0, 0.0, 13.0, 60.0, 0.0, 55.0, 60.0, 0.0, 0.0, 90, 0.0, 42.0, 90.0, 0.0, 84.0, 90.0, 0.0", "16.0, 40.0, 100.0, 58.0, 40.0, 100.0, 100.0, 40.0, 100.0, 29.0, 70.0, 100.0, 71.0, 70.0, 100.0, 16.0, 100.0, 100.0, 58.0, 100.0, 100.0, 100.0, 100.0, 100.0", 0, 2.0, 1
1, 80, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 50.0", "0.25, 1.0", "8.0, 25.0", "0.1, 0.02", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "60.0, 80.0, 45.0, 70.0", "70, 15, 15, 20, 20, 15, 15, 70", 0.15, "15.0, 15.0, 50.0, 40.0, 10.0, 45.0", 8, "0.0, 30.0, 0.0, 42.0, 30.0, 0.0, 84.0, 30.0, 0.0, 13.0, 60.0, 0.0, 55.0, 60.0, 0.0, 0.0, 90, 0.0, 42.0, 90.0, 0.0, 84.0, 90.0, 0.0", "16.0, 40.0, 100.0, 58.0, 40.0, 100.0, 100.0, 40.0, 100.0, 29.0, 70.0, 100.0, 71.0, 70.0, 100.0, 16.0, 100.0, 100.0, 58.0, 100.0, 100.0, 100.0, 100.0, 100.0", 0, 2.0, 1
1 timestep maxIter minAlt discretizationStep protectedRange initialStepSize barrierGain barrierExponent collisionRadius comRange alphaDist betaDist alphaTilt betaTilt domainMin domainMax objectivePos objectiveVar sensorPerformanceMinimum initialPositions numObstacles obstacleMin obstacleMax useDoubleIntegrator dampingCoeff useFixedTopology
2 1 80 35.0 0.1 2.0 6 1 1 8.0, 8.0 35.0, 35.0 80.0, 50.0 0.25, 1.0 8.0, 25.0 0.1, 0.02 0.0, 0.0, 0.0 100.0, 100.0, 100.0 60.0, 80.0, 45.0, 70.0 70, 15, 15, 20, 20, 15, 15, 70 0.15 15.0, 15.0, 50.0, 40.0, 10.0, 45.0 8 0.0, 30.0, 0.0, 42.0, 30.0, 0.0, 84.0, 30.0, 0.0, 13.0, 60.0, 0.0, 55.0, 60.0, 0.0, 0.0, 90, 0.0, 42.0, 90.0, 0.0, 84.0, 90.0, 0.0 16.0, 40.0, 100.0, 58.0, 40.0, 100.0, 100.0, 40.0, 100.0, 29.0, 70.0, 100.0, 71.0, 70.0, 100.0, 16.0, 100.0, 100.0, 58.0, 100.0, 100.0, 100.0, 100.0, 100.0 0 2.0 1
+1 -1
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, useDoubleIntegrator, dampingCoeff, useFixedTopology
1, 125, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 50.0", "0.25, 1.0", "8.0, 25.0", "0.1, 0.02", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "30.0, 80.0", "60, 20, 20, 30", 0.15, "65.0, 15.0, 65.0, 65.0, 15.0, 45.0", 3, "0.0, 25.0, 55.0, 40.0, 10.0, 0.0, 40.0, 45.0, 60.0", "100.0, 70.0, 60.0, 45.0, 80.0, 55.0, 100.0, 50.0, 100.0", 0, 2.0, 1
1, 125, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 50.0", "0.25, 1.0", "8.0, 25.0", "0.1, 0.02", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "30.0, 80.0", "60, 20, 20, 30", 0.15, "65.0, 15.0, 65.0, 65.0, 15.0, 45.0", 3, "0.0, 25.0, 55.0, 40.0, 10.0, 0.0, 40.0, 45.0, 60.0", "100.0, 70.0, 60.0, 45.0, 80.0, 55.0, 100.0, 50.0, 100.0", 0, 2.0, 1
1 timestep maxIter minAlt discretizationStep protectedRange initialStepSize barrierGain barrierExponent collisionRadius comRange alphaDist betaDist alphaTilt betaTilt domainMin domainMax objectivePos objectiveVar sensorPerformanceMinimum initialPositions numObstacles obstacleMin obstacleMax useDoubleIntegrator dampingCoeff useFixedTopology
2 1 125 35.0 0.1 2.0 6 1 1 8.0, 8.0 35.0, 35.0 80.0, 50.0 0.25, 1.0 8.0, 25.0 0.1, 0.02 0.0, 0.0, 0.0 100.0, 100.0, 100.0 30.0, 80.0 60, 20, 20, 30 0.15 65.0, 15.0, 65.0, 65.0, 15.0, 45.0 3 0.0, 25.0, 55.0, 40.0, 10.0, 0.0, 40.0, 45.0, 60.0 100.0, 70.0, 60.0, 45.0, 80.0, 55.0, 100.0, 50.0, 100.0 0 2.0 1
+1 -1
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, useDoubleIntegrator, dampingCoeff, useFixedTopology
1, 125, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 50.0", "0.25, 1.0", "8.0, 25.0", "0.1, 0.02", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "30.0, 80.0", "60, 20, 20, 30", 0.15, "90.0, 10.0, 50.0, 65.0, 15.0, 45.0", 4, "0.0, 30.0, 0.0, 70.0, 30.0, 0.0, 0.0, 60.0, 0.0, 55.0, 60.0, 0.0", "50.0, 40.0, 100.0, 100.0, 40.0, 100.0, 35.0, 70.0, 100.0, 100.0, 70.0, 100.0", 0, 2.0, 1
1, 125, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 50.0", "0.25, 1.0", "8.0, 25.0", "0.1, 0.02", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "30.0, 80.0", "60, 20, 20, 30", 0.15, "90.0, 10.0, 50.0, 65.0, 15.0, 45.0", 4, "0.0, 30.0, 0.0, 70.0, 30.0, 0.0, 0.0, 60.0, 0.0, 55.0, 60.0, 0.0", "50.0, 40.0, 100.0, 100.0, 40.0, 100.0, 35.0, 70.0, 100.0, 100.0, 70.0, 100.0", 0, 2.0, 1
1 timestep maxIter minAlt discretizationStep protectedRange initialStepSize barrierGain barrierExponent collisionRadius comRange alphaDist betaDist alphaTilt betaTilt domainMin domainMax objectivePos objectiveVar sensorPerformanceMinimum initialPositions numObstacles obstacleMin obstacleMax useDoubleIntegrator dampingCoeff useFixedTopology
2 1 125 35.0 0.1 2.0 6 1 1 8.0, 8.0 35.0, 35.0 80.0, 50.0 0.25, 1.0 8.0, 25.0 0.1, 0.02 0.0, 0.0, 0.0 100.0, 100.0, 100.0 30.0, 80.0 60, 20, 20, 30 0.15 90.0, 10.0, 50.0, 65.0, 15.0, 45.0 4 0.0, 30.0, 0.0, 70.0, 30.0, 0.0, 0.0, 60.0, 0.0, 55.0, 60.0, 0.0 50.0, 40.0, 100.0, 100.0, 40.0, 100.0, 35.0, 70.0, 100.0, 100.0, 70.0, 100.0 0 2.0 1
+2 -2
View File
@@ -198,8 +198,8 @@ else
% 5. Unconstrained gradient-ascent step for each agent
for ii = 1:size(sim.agents, 1)
sim.agents{ii} = sim.agents{ii}.run(sim.domain, sim.partitioning, ...
sim.timestepIndex, ii, sim.agents, ...
sim.useDoubleIntegrator, sim.dampingCoeff, sim.timestep);
sim.timestepIndex, ii, ...
sim.useDoubleIntegrator, sim.dampingCoeff, sim.timestep, sim.optimizeSensorPointing);
end
% 6. Apply CBF safety filter (collision / comms / domain constraints via QP)
+28
View File
@@ -0,0 +1,28 @@
function controller = controllerAnalysis(resultsPath)
arguments (Input)
resultsPath (1, 1) string;
end
arguments (Output)
controller table;
end
% Measure intervals between issuing commands from the controller
% (make sure this is ~4-5 seconds at minimum to avoid overwhelming the UAV autopilot)
r = dir(resultsPath);
controllerPath = fullfile(r(startsWith({r.name}, 'controller_')).folder, r(startsWith({r.name}, 'controller_')).name);
controllerPath = dir(controllerPath);
controllerPath = fullfile(controllerPath(endsWith({controllerPath.name}, '_controller_log.txt')).folder, controllerPath(endsWith({controllerPath.name}, '_controller_log.txt')).name);
controller = readControllerLogs(controllerPath);
rpIdx = startsWith(controller.message, "Iteration duration: ");
s = split(controller.message(rpIdx), "Iteration duration: ");
s = split(s(:, 2), ' s');
s = duration(strcat("00:", s(:, 1)), "InputFormat", "mm:ss.SSS");
s.Format = "mm:ss.SSS";
fprintf("Minimum command spacing: %2.3f seconds\n", seconds(min(s)));
fprintf("Maximum command spacing: %2.3f seconds\n", seconds(max(s)));
fprintf("Mean command spacing: %2.3f seconds\n", seconds(mean(s)));
fprintf("Median command spacing: %2.3f seconds\n", seconds(median(s)));
if seconds(min(s)) < 4
warning("Minimum command spacing %2.3f questionably short for AERPAW", seconds(min(s)));
end
end
+183 -8
View File
@@ -1,9 +1,12 @@
function [f, R] = plotRadioLogs(resultsPath)
function [f, fDist, R] = plotRadioLogs(resultsPath, G, tLim)
arguments (Input)
resultsPath (1, 1) string;
G cell = {};
tLim (1, 2) datetime = [datetime(-Inf, 'ConvertFrom', 'datenum'), datetime(Inf, 'ConvertFrom', 'datenum')];
end
arguments (Output)
f (1, 1) matlab.ui.Figure;
fDist (1, 1) matlab.ui.Figure;
R cell;
end
@@ -40,11 +43,44 @@ function [f, R] = plotRadioLogs(resultsPath)
metricNames = ["SNR", "Power", "Quality", "PathLoss", "NoiseFloor", "FreqOffset"];
yLabels = ["SNR (dB)", "Power (dB)", "Quality", "Path Loss (dB)", "Noise Floor (dB)", "Freq Offset (MHz)"];
nMetrics = numel(metricNames);
% --- Time-based figure ---
f = figure;
tl = tiledlayout(numel(metricNames), 1, 'TileSpacing', 'compact', 'Padding', 'compact');
tl = tiledlayout(nMetrics + 1, 1, 'TileSpacing', 'compact', 'Padding', 'compact');
for mi = 1:numel(metricNames)
% Distance vs time tile (first)
ax = nexttile(tl);
hold(ax, 'on'); grid(ax, 'on');
legendEntries = string.empty;
ci = 1;
if ~isempty(G)
for rxIdx = 1:nUAV
tbl = R{rxIdx};
txIDs = unique(tbl.TxUAVID);
for ti = 1:numel(txIDs)
txID = txIDs(ti);
rows = tbl(tbl.TxUAVID == txID, :);
rows = rows(rows.Timestamp >= tLim(1) & rows.Timestamp <= tLim(2), :);
if isempty(rows), continue; end
[~, ia] = unique(rows.Timestamp);
[radioPt, dist] = pairDist(rows(ia, :), G);
if isempty(dist) || all(isnan(dist)), continue; end
valid = ~isnan(dist);
si = mod(ci - 1, numel(styles)) + 1;
plot(ax, datetime(radioPt(valid), 'ConvertFrom', 'posixtime'), dist(valid), ...
styles(si), 'Color', colors(ci, :), 'MarkerSize', 3, 'LineWidth', 0.5);
legendEntries(end+1) = sprintf("TX %d → RX %d", txID, rows.RxUAVID(1)); %#ok<AGROW>
ci = ci + 1;
end
end
end
ylabel(ax, 'Distance (m)');
xlabel(ax, 'Time');
legend(ax, legendEntries, 'Location', 'best');
hold(ax, 'off');
for mi = 1:nMetrics
ax = nexttile(tl);
hold(ax, 'on');
grid(ax, 'on');
@@ -57,23 +93,32 @@ function [f, R] = plotRadioLogs(resultsPath)
for ti = 1:numel(txIDs)
txID = txIDs(ti);
rows = tbl(tbl.TxUAVID == txID, :);
rows = rows(rows.Timestamp >= tLim(1) & rows.Timestamp <= tLim(2), :);
vals = rows.(metricNames(mi));
valid = ~isnan(vals);
rows = rows(valid, :);
vals = vals(valid);
% Skip if all NaN for this metric
if all(isnan(vals))
if isempty(rows)
continue;
end
si = mod(ci - 1, numel(styles)) + 1;
plot(ax, rows.Timestamp, vals, styles(si), ...
'Color', colors(ci, :), 'MarkerSize', 3, 'LineWidth', 1);
'Color', colors(ci, :), 'MarkerSize', 3, 'LineWidth', 0.5);
legendEntries(end+1) = sprintf("TX %d → RX %d", txID, tbl.RxUAVID(1)); %#ok<AGROW>
% Median per 1/3-second time bin
[t_med, v_med] = timeBinMedian(posixtime(rows.Timestamp), vals, 1/3);
plot(ax, datetime(t_med, 'ConvertFrom', 'posixtime'), v_med, '-', ...
'Color', 'r', 'LineWidth', 2);
legendEntries(end+1) = sprintf("TX %d → RX %d (median)", txID, tbl.RxUAVID(1)); %#ok<AGROW>
ci = ci + 1;
end
end
ylabel(ax, yLabels(mi));
if mi == numel(metricNames)
if mi == nMetrics
xlabel(ax, 'Time');
end
legend(ax, legendEntries, 'Location', 'best');
@@ -81,4 +126,134 @@ function [f, R] = plotRadioLogs(resultsPath)
end
title(tl, 'Radio Channel Metrics');
end
% --- Distance-based figure ---
fDist = figure;
if isempty(G)
return;
end
tl2 = tiledlayout(nMetrics + 1, 1, 'TileSpacing', 'compact', 'Padding', 'compact');
% Distance vs time tile (first)
ax = nexttile(tl2);
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, :);
rows = rows(rows.Timestamp >= tLim(1) & rows.Timestamp <= tLim(2), :);
if isempty(rows), continue; end
[~, ia] = unique(rows.Timestamp);
[radioPt, dist] = pairDist(rows(ia, :), G);
if isempty(dist) || all(isnan(dist)), continue; end
valid = ~isnan(dist);
si = mod(ci - 1, numel(styles)) + 1;
plot(ax, datetime(radioPt(valid), 'ConvertFrom', 'posixtime'), dist(valid), ...
styles(si), 'Color', colors(ci, :), 'MarkerSize', 3, 'LineWidth', 0.5);
legendEntries(end+1) = sprintf("TX %d → RX %d", txID, rows.RxUAVID(1)); %#ok<AGROW>
ci = ci + 1;
end
end
ylabel(ax, 'Distance (m)');
xlabel(ax, 'Time');
legend(ax, legendEntries, 'Location', 'best');
hold(ax, 'off');
for mi = 1:nMetrics
ax = nexttile(tl2);
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, :);
if isempty(rows)
continue;
end
rows = rows(rows.Timestamp >= tLim(1) & rows.Timestamp <= tLim(2), :);
if isempty(rows)
continue;
end
vals = rows.(metricNames(mi));
valid = ~isnan(vals);
rows = rows(valid, :);
vals = vals(valid);
if isempty(rows)
continue;
end
[radioPt, dist] = pairDist(rows, G);
if isempty(dist) || all(isnan(dist)), continue; end
% Drop points where GPS interpolation returned NaN
validDist = ~isnan(dist);
rowTs = radioPt(validDist);
dist = dist(validDist);
vals = vals(validDist);
si = mod(ci - 1, numel(styles)) + 1;
scatter(ax, dist, vals, 9, colors(ci, :), strrep(styles(si), "-", ""), 'filled');
legendEntries(end+1) = sprintf("TX %d → RX %d", txID, rows.RxUAVID(1)); %#ok<AGROW>
% Median per 1/3-second time bin, plotted against median distance
[~, dv_med] = timeBinMedian(rowTs, [dist, vals], 1/3);
[d_med, si_sort] = sort(dv_med(:, 1));
v_med = dv_med(si_sort, 2);
plot(ax, d_med, v_med, '-', 'Color', 'r', 'LineWidth', 2);
legendEntries(end+1) = sprintf("TX %d → RX %d (median)", txID, rows.RxUAVID(1)); %#ok<AGROW>
ci = ci + 1;
end
end
ylabel(ax, yLabels(mi));
if mi == nMetrics
xlabel(ax, 'Distance (m)');
end
legend(ax, legendEntries, 'Location', 'best');
hold(ax, 'off');
end
title(tl2, 'Radio Channel Metrics vs Distance');
end
function [radioPt, dist] = pairDist(rows, G)
% Interpolate GPS-based inter-UAV distance at each row's timestamp.
radioPt = []; dist = [];
txGpsIdx = double(rows.TxUAVID(1)) + 1;
rxGpsIdx = double(rows.RxUAVID(1)) + 1;
if txGpsIdx > numel(G) || rxGpsIdx > numel(G), return; end
Gtx = G{txGpsIdx};
Grx = G{rxGpsIdx};
if ~ismember('East', Gtx.Properties.VariableNames) || ...
~ismember('East', Grx.Properties.VariableNames), return; end
txTs = Gtx.Timestamp; txTs.TimeZone = '';
rxTs = Grx.Timestamp; rxTs.TimeZone = '';
txPt = posixtime(txTs);
rxPt = posixtime(rxTs);
radioPt = posixtime(rows.Timestamp);
validTx = ~isnan(Gtx.East);
validRx = ~isnan(Grx.East);
txE = interp1(txPt(validTx), Gtx.East(validTx), radioPt, 'linear', NaN);
txN = interp1(txPt(validTx), Gtx.North(validTx), radioPt, 'linear', NaN);
txU = interp1(txPt(validTx), Gtx.Up(validTx), radioPt, 'linear', NaN);
rxE = interp1(rxPt(validRx), Grx.East(validRx), radioPt, 'linear', NaN);
rxN = interp1(rxPt(validRx), Grx.North(validRx), radioPt, 'linear', NaN);
rxU = interp1(rxPt(validRx), Grx.Up(validRx), radioPt, 'linear', NaN);
dist = vecnorm([txE - rxE, txN - rxN, txU - rxU], 2, 2);
end
+34
View File
@@ -70,6 +70,40 @@ function R = readRadioLogs(logPath)
R = sortrows(R, "Timestamp");
% Reconstruct per-measurement timestamps within GNURadio processing batches.
% The flowgraph accumulates one full PN sequence (4095 chips at samp_rate/sps)
% per measurement, but outputs the whole batch simultaneously with a single
% wall-clock timestamp. We reassign timestamps by counting backward from the
% batch processing time at the known PN period interval.
pn_period = 4095 / (2e6 / 16); % 32.76 ms per PN correlation period
for txId = unique(R.TxUAVID)'
rows = find(R.TxUAVID == txId);
if numel(rows) < 2, continue; end
dt = seconds(diff(R.Timestamp(rows)));
break_pos = [1; find(dt > 0.5) + 1];
end_pos = [break_pos(2:end) - 1; numel(rows)];
for b = 1:numel(break_pos)
idx = rows(break_pos(b) : end_pos(b));
batch_ts = posixtime(R.Timestamp(idx));
t_ref = max(batch_ts);
% Multiple metric files share the same processing timestamp for
% each PN period, so group by unique original timestamp rather
% than treating every row as a separate PN period.
[~, ~, group_id] = unique(batch_ts);
n_groups = max(group_id);
new_ts = t_ref - (n_groups - 1 : -1 : 0)' * pn_period;
for g = 1:n_groups
R.Timestamp(idx(group_id == g)) = ...
datetime(new_ts(g), 'ConvertFrom', 'posixtime');
end
end
end
% Remove rows during defined guard period between TDM shifts
R(R.TxUAVID == -1, :) = [];
+9 -23
View File
@@ -1,33 +1,16 @@
%% Plot AERPAW logs (trajectory, radio)
resultsPath = fullfile(matlab.project.rootProject().RootFolder, "sandbox", "two_around_wall"); % Define path to results copied from AERPAW platform
% Measure intervals between issuing commands from the controller
% (make sure this is ~4-5 seconds at minimum to avoid overwhelming the UAV autopilot)
r = dir(resultsPath);
controllerPath = fullfile(r(startsWith({r.name}, 'controller_')).folder, r(startsWith({r.name}, 'controller_')).name);
controllerPath = dir(controllerPath);
controllerPath = fullfile(controllerPath(endsWith({controllerPath.name}, '_controller_log.txt')).folder, controllerPath(endsWith({controllerPath.name}, '_controller_log.txt')).name);
controller = readControllerLogs(controllerPath);
rpIdx = startsWith(controller.message, "Iteration duration: ");
s = split(controller.message(rpIdx), "Iteration duration: ");
s = split(s(:, 2), ' s');
s = duration(strcat("00:", s(:, 1)), "InputFormat", "mm:ss.SSS");
s.Format = "mm:ss.SSS";
fprintf("Minimum command spacing: %2.3f seconds\n", seconds(min(s)));
fprintf("Maximum command spacing: %2.3f seconds\n", seconds(max(s)));
fprintf("Mean command spacing: %2.3f seconds\n", seconds(mean(s)));
fprintf("Median command spacing: %2.3f seconds\n", seconds(median(s)));
if seconds(min(s)) < 4
warning("Minimum command spacing %2.3f questionably short for AERPAW", seconds(min(s)));
end
% Check timeline in controller logs
controller = controllerAnalysis(resultsPath);
% Plot GPS logged data and scenario information (domain, objective, obstacles)
seaToGroundLevel = 110; % measured approximately from USGS national map viewer
plotWholeFlight = true; % do not attempt to automatically trim initial and final positioning and landing from flight plot (buggy)
[fGlobe, G] = plotGpsLogs(resultsPath, seaToGroundLevel, true);
% Plot radio statistics
[fRadio, R] = plotRadioLogs(resultsPath);
% Plot radio statistics (time-based and distance-based)
[fRadio, fRadioDist, R] = plotRadioLogs(resultsPath, G, controller.timestamp([1, end]));
%% Run simulation
% Run miSim using same AERPAW scenario definition CSV
@@ -54,7 +37,7 @@ for ii = 1:size(agents, 1)
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);
agents{ii} = agents{ii}.initialize(params.initialPositions((((ii - 1) * 3) + 1):(ii * 3)), collisionGeometry, sensorModel, params.comRange(ii), params.maxIter, params.initialStepSize, 5.0, sprintf("Agent %d", ii), plotCommsGeometry);
end
% Create obstacles
@@ -81,9 +64,12 @@ copyobj(sim.f.Children, comparison);
% Plot trajectories on top
for ii = 1:size(G, 1)
gpsTimes = G{ii}.Timestamp;
gpsTimes.TimeZone = '';
inRange = gpsTimes >= controller.timestamp(1) & gpsTimes <= controller.timestamp(end);
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);
plot3(comparison.Children(1).Children(sim.spatialPlotIndices(jj)), G{ii}.East(inRange), G{ii}.North(inRange), G{ii}.Up(inRange) + seaToGroundLevel, 'Color', 'r', 'LineWidth', 1);
hold(comparison.Children.Children(sim.spatialPlotIndices(jj)), "off");
end
end
+29
View File
@@ -0,0 +1,29 @@
function [t_med, v_med] = timeBinMedian(t, v, binWidth)
% Compute median of each column of v within fixed-width time bins.
%
% t - (N,1) posixtime values
% v - (N,K) data matrix; one column per quantity
% binWidth - scalar bin width in seconds
%
% t_med - (B,1) median time of each non-empty bin
% v_med - (B,K) median of each column per non-empty bin
edges = (floor(min(t) / binWidth) * binWidth) : binWidth : ...
(floor(max(t) / binWidth) * binWidth + binWidth);
bins = discretize(t, edges);
nBins = numel(edges) - 1;
K = size(v, 2);
t_all = NaN(nBins, 1);
v_all = NaN(nBins, K);
for bi = 1:nBins
mask = bins == bi;
if ~any(mask), continue; end
t_all(bi) = median(t(mask));
v_all(bi,:) = median(v(mask,:), 1);
end
ok = ~isnan(t_all);
t_med = t_all(ok);
v_med = v_all(ok, :);
end