Compare commits
70 Commits
6b5d33962b
...
spawc-2026
| Author | SHA1 | Date | |
|---|---|---|---|
| b753f05d77 | |||
| 2ca0c286cd | |||
| f23675a54c | |||
| 8c3b853895 | |||
| e77b05bc0f | |||
| 6b74347411 | |||
| a3837a6ef4 | |||
| 01f2af9102 | |||
| 0d02e5d1f5 | |||
| 2a0e2e500f | |||
| ca891a809f | |||
| 771575560f | |||
| f003528a9c | |||
| 102f23316d | |||
| 24113f282f | |||
| b4cd7613ec | |||
| 97e34264dd | |||
| c5f1dcdb51 | |||
| e5fa2fa827 | |||
| fdd9b49e34 | |||
| ea034dd748 | |||
| b09f882369 | |||
| cdbfaebc17 | |||
| 1b4fec0f72 | |||
| cd3463d479 | |||
| 624b2bdcb2 | |||
| 6da0c97abf | |||
| 3c775cf814 | |||
| 1562fdc351 | |||
| a706857374 | |||
| 8c5811ff6a | |||
| 14201aff5d | |||
| 532e37f133 | |||
| 986f4e2dcf | |||
| c18b470706 | |||
| 438ebda388 | |||
| f40d2bfd84 | |||
| 117d34590e | |||
| 7da35c5cda | |||
| 05ac8a6e97 | |||
| 813b124c47 | |||
| 5408a31d56 | |||
| 1d4f59734b | |||
| 5e52292b71 | |||
| f1c2df31d9 | |||
| c19f65c3a1 | |||
| dbba95c6a9 | |||
| 1ada914384 | |||
| 58d87cd16f | |||
| cec6458f7c | |||
| 9385b9bd06 | |||
| d25287cdf9 | |||
| 61e440b594 | |||
| dbb4ba178a | |||
| cde86065e9 | |||
| 87d925ba5c | |||
| 0e9f494c50 | |||
| bcfaad1817 | |||
| 1475d9e7d1 | |||
| ee238f239d | |||
| 4cdcb16ee3 | |||
| 9705c1e952 | |||
| 8002336ba1 | |||
| cb61ddb161 | |||
| 4d08e2c88a | |||
| c8b54a30aa | |||
| 1ae617d5f7 | |||
| fa5d63361c | |||
| 8abd009aed | |||
| 20417f240c |
1
.gitignore
vendored
1
.gitignore
vendored
@@ -48,6 +48,7 @@ sandbox/*
|
|||||||
|
|
||||||
# Figures
|
# Figures
|
||||||
*.fig
|
*.fig
|
||||||
|
*.png
|
||||||
|
|
||||||
# Python Virtual Environment
|
# Python Virtual Environment
|
||||||
aerpaw/venv/
|
aerpaw/venv/
|
||||||
|
|||||||
3
.gitmodules
vendored
3
.gitmodules
vendored
@@ -1,3 +0,0 @@
|
|||||||
[submodule "aerpaw/aerpawlib"]
|
|
||||||
path = aerpaw/aerpawlib
|
|
||||||
url = https://github.com/morzack/aerpawlib-vehicle-control.git
|
|
||||||
|
|||||||
@@ -6,6 +6,8 @@ classdef agent
|
|||||||
% State
|
% State
|
||||||
lastPos = NaN(1, 3); % position from previous timestep
|
lastPos = NaN(1, 3); % position from previous timestep
|
||||||
pos = NaN(1, 3); % current position
|
pos = NaN(1, 3); % current position
|
||||||
|
vel = zeros(1, 3); % velocity (double-integrator mode)
|
||||||
|
lastVel = zeros(1, 3); % pre-step velocity (double-integrator mode)
|
||||||
|
|
||||||
% Sensor
|
% Sensor
|
||||||
sensorModel;
|
sensorModel;
|
||||||
|
|||||||
@@ -15,6 +15,9 @@ function obj = initialize(obj, pos, collisionGeometry, sensorModel, comRange, ma
|
|||||||
end
|
end
|
||||||
|
|
||||||
obj.pos = pos;
|
obj.pos = pos;
|
||||||
|
obj.lastPos = pos;
|
||||||
|
obj.vel = zeros(1, 3);
|
||||||
|
obj.lastVel = zeros(1, 3);
|
||||||
obj.collisionGeometry = collisionGeometry;
|
obj.collisionGeometry = collisionGeometry;
|
||||||
obj.sensorModel = sensorModel;
|
obj.sensorModel = sensorModel;
|
||||||
obj.label = label;
|
obj.label = label;
|
||||||
|
|||||||
39
@agent/run.m
39
@agent/run.m
@@ -1,4 +1,4 @@
|
|||||||
function obj = run(obj, domain, partitioning, timestepIndex, index, agents)
|
function obj = run(obj, domain, partitioning, timestepIndex, index, agents, useDoubleIntegrator, dampingCoeff, dt)
|
||||||
arguments (Input)
|
arguments (Input)
|
||||||
obj (1, 1) {mustBeA(obj, "agent")};
|
obj (1, 1) {mustBeA(obj, "agent")};
|
||||||
domain (1, 1) {mustBeGeometry};
|
domain (1, 1) {mustBeGeometry};
|
||||||
@@ -6,11 +6,21 @@ function obj = run(obj, domain, partitioning, timestepIndex, index, agents)
|
|||||||
timestepIndex (1, 1) double;
|
timestepIndex (1, 1) double;
|
||||||
index (1, 1) double;
|
index (1, 1) double;
|
||||||
agents (:, 1) {mustBeA(agents, "cell")};
|
agents (:, 1) {mustBeA(agents, "cell")};
|
||||||
|
useDoubleIntegrator (1, 1) logical = false;
|
||||||
|
dampingCoeff (1, 1) double = 2.0;
|
||||||
|
dt (1, 1) double = 1.0;
|
||||||
end
|
end
|
||||||
arguments (Output)
|
arguments (Output)
|
||||||
obj (1, 1) {mustBeA(obj, "agent")};
|
obj (1, 1) {mustBeA(obj, "agent")};
|
||||||
end
|
end
|
||||||
|
|
||||||
|
% Always update lastPos/lastVel so constrainMotion evaluates barriers at
|
||||||
|
% the correct (most recent) position, even when this agent has no partition.
|
||||||
|
obj.lastPos = obj.pos;
|
||||||
|
if useDoubleIntegrator
|
||||||
|
obj.lastVel = obj.vel;
|
||||||
|
end
|
||||||
|
|
||||||
% Collect objective function values across partition
|
% Collect objective function values across partition
|
||||||
partitionMask = partitioning == index;
|
partitionMask = partitioning == index;
|
||||||
if ~any(partitionMask(:))
|
if ~any(partitionMask(:))
|
||||||
@@ -75,20 +85,25 @@ function obj = run(obj, domain, partitioning, timestepIndex, index, agents)
|
|||||||
targetRate = obj.initialStepSize - obj.stepDecayRate * timestepIndex; % slow down as you get closer
|
targetRate = obj.initialStepSize - obj.stepDecayRate * timestepIndex; % slow down as you get closer
|
||||||
gradNorm = norm(gradC);
|
gradNorm = norm(gradC);
|
||||||
|
|
||||||
% Compute unconstrained next position.
|
% Compute unconstrained next state
|
||||||
% Guard against near-zero gradient: when sensor performance is saturated
|
if useDoubleIntegrator
|
||||||
% or near-zero across the whole partition, rateFactor -> Inf and pNext
|
% Double-integrator: gradient produces desired acceleration with damping
|
||||||
% explodes. Stay put instead.
|
if gradNorm < 1e-100
|
||||||
if gradNorm < 1e-100
|
a_gradient = zeros(1, 3);
|
||||||
pNext = obj.pos;
|
else
|
||||||
|
% Scale so steady-state step ≈ targetRate (matching SI behavior)
|
||||||
|
a_gradient = (targetRate * dampingCoeff / (gradNorm * dt)) * gradC;
|
||||||
|
end
|
||||||
|
% Semi-implicit Euler: unconditionally stable for any dampingCoeff and dt
|
||||||
|
obj.vel = (obj.vel + a_gradient * dt) / (1 + dampingCoeff * dt);
|
||||||
|
obj.pos = obj.lastPos + obj.vel * dt;
|
||||||
else
|
else
|
||||||
pNext = obj.pos + (targetRate / gradNorm) * gradC;
|
% Single-integrator: gradient directly sets position step
|
||||||
|
if gradNorm >= 1e-100
|
||||||
|
obj.pos = obj.pos + (targetRate / gradNorm) * gradC;
|
||||||
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
% Move to next position
|
|
||||||
obj.lastPos = obj.pos;
|
|
||||||
obj.pos = pNext;
|
|
||||||
|
|
||||||
% Reinitialize collision geometry in the new position
|
% Reinitialize collision geometry in the new position
|
||||||
d = obj.pos - obj.collisionGeometry.center;
|
d = obj.pos - obj.collisionGeometry.center;
|
||||||
if isa(obj.collisionGeometry, "rectangularPrism")
|
if isa(obj.collisionGeometry, "rectangularPrism")
|
||||||
|
|||||||
@@ -8,118 +8,128 @@ function [obj] = constrainMotion(obj)
|
|||||||
|
|
||||||
nAgents = size(obj.agents, 1);
|
nAgents = size(obj.agents, 1);
|
||||||
|
|
||||||
if nAgents < 2
|
% Compute current velocity and desired control input
|
||||||
nAAPairs = 0;
|
v = zeros(nAgents, 3); % current velocity (for drift term in DI mode)
|
||||||
else
|
u_desired = zeros(nAgents, 3); % desired control: velocity (SI) or acceleration (DI)
|
||||||
nAAPairs = nchoosek(nAgents, 2); % unique agent/agent pairs
|
|
||||||
end
|
|
||||||
|
|
||||||
% Compute velocity matrix from unconstrained gradient-ascent step
|
|
||||||
v = zeros(nAgents, 3);
|
|
||||||
for ii = 1:nAgents
|
for ii = 1:nAgents
|
||||||
v(ii, :) = (obj.agents{ii}.pos - obj.agents{ii}.lastPos) ./ obj.timestep;
|
if obj.useDoubleIntegrator
|
||||||
|
v(ii, :) = obj.agents{ii}.lastVel;
|
||||||
|
u_desired(ii, :) = (obj.agents{ii}.vel - obj.agents{ii}.lastVel) / obj.timestep;
|
||||||
|
else
|
||||||
|
v(ii, :) = (obj.agents{ii}.pos - obj.agents{ii}.lastPos) ./ obj.timestep;
|
||||||
|
u_desired(ii, :) = v(ii, :);
|
||||||
|
end
|
||||||
end
|
end
|
||||||
if all(isnan(v), "all") || all(v == zeros(nAgents, 3), "all")
|
if ~obj.useDoubleIntegrator && (all(isnan(v), "all") || all(v == zeros(nAgents, 3), "all"))
|
||||||
% Agents are not attempting to move, so there is no motion to be
|
% Single-integrator: agents are not attempting to move
|
||||||
% constrained
|
return;
|
||||||
|
end
|
||||||
|
if obj.useDoubleIntegrator && all(u_desired == 0, "all") && all(v == 0, "all")
|
||||||
|
% Double-integrator: no desired acceleration and no existing velocity
|
||||||
return;
|
return;
|
||||||
end
|
end
|
||||||
|
|
||||||
% Initialize QP based on number of agents and obstacles
|
% Initialize QP based on number of agents and obstacles
|
||||||
nAOPairs = nAgents * size(obj.obstacles, 1); % unique agent/obstacle pairs
|
|
||||||
nADPairs = nAgents * 6; % agents x (4 walls + 1 floor + 1 ceiling)
|
|
||||||
nLNAPairs = sum(obj.constraintAdjacencyMatrix, "all") - nAgents;
|
|
||||||
total = nAAPairs + nAOPairs + nADPairs + nLNAPairs;
|
|
||||||
kk = 1;
|
kk = 1;
|
||||||
A = zeros(total, 3 * nAgents);
|
A = zeros(obj.numBarriers, 3 * nAgents);
|
||||||
b = zeros(total, 1);
|
b = zeros(obj.numBarriers, 1);
|
||||||
|
|
||||||
% Set up collision avoidance constraints
|
% Set up collision avoidance constraints
|
||||||
h = NaN(nAgents, nAgents);
|
h = NaN(nAgents, nAgents);
|
||||||
h(logical(eye(nAgents))) = 0; % self value is 0
|
h(logical(eye(nAgents))) = 0; % self value is 0
|
||||||
for ii = 1:(nAgents - 1)
|
for ii = 1:(nAgents - 1)
|
||||||
for jj = (ii + 1):nAgents
|
for jj = (ii + 1):nAgents
|
||||||
h(ii, jj) = norm(obj.agents{ii}.pos - obj.agents{jj}.pos)^2 - (obj.agents{ii}.collisionGeometry.radius + obj.agents{jj}.collisionGeometry.radius)^2;
|
h(ii, jj) = norm(obj.agents{ii}.lastPos - obj.agents{jj}.lastPos)^2 - (obj.agents{ii}.collisionGeometry.radius + obj.agents{jj}.collisionGeometry.radius)^2;
|
||||||
h(jj, ii) = h(ii, jj);
|
h(jj, ii) = h(ii, jj);
|
||||||
|
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.pos - obj.agents{jj}.pos);
|
A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.lastPos - obj.agents{jj}.lastPos);
|
||||||
A(kk, (3 * jj - 2):(3 * jj)) = -A(kk, (3 * ii - 2):(3 * ii));
|
A(kk, (3 * jj - 2):(3 * jj)) = -A(kk, (3 * ii - 2):(3 * ii));
|
||||||
% Slack derived from existing params: recovery velocity = max gradient approach velocity.
|
% Slack derived from existing params: recovery velocity = max gradient approach velocity.
|
||||||
% Correction splits between 2 agents, so |A| = 2*r_sum
|
% Correction splits between 2 agents, so |A| = 2*r_sum
|
||||||
r_sum_ij = obj.agents{ii}.collisionGeometry.radius + obj.agents{jj}.collisionGeometry.radius;
|
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;
|
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
|
if norm(A(kk, :)) < 1e-9
|
||||||
% Agents are coincident: A-row is zero, so b < 0 would make
|
% Agents are coincident: A-row is zero, so b < 0 would make
|
||||||
% 0 ≤ b unsatisfiable. Fall back to b = 0 (no correction possible).
|
% 0 ≤ b unsatisfiable. Fall back to b = 0 (no correction possible).
|
||||||
b(kk) = 0;
|
b(kk) = 0;
|
||||||
else
|
else
|
||||||
b(kk) = obj.barrierGain * max(slack, h(ii, jj))^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(hMin, h(ii, jj))^obj.barrierExponent;
|
||||||
end
|
end
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
idx = length(h(triu(true(size(h)), 1)));
|
||||||
|
obj.barriers(1:idx, obj.timestepIndex) = h(triu(true(size(h)), 1));
|
||||||
|
idx = idx + 1;
|
||||||
|
|
||||||
hObs = NaN(nAgents, size(obj.obstacles, 1));
|
hObs = NaN(nAgents, size(obj.obstacles, 1));
|
||||||
% Set up obstacle avoidance constraints
|
% Set up obstacle avoidance constraints
|
||||||
for ii = 1:nAgents
|
for ii = 1:nAgents
|
||||||
for jj = 1:size(obj.obstacles, 1)
|
for jj = 1:size(obj.obstacles, 1)
|
||||||
% find closest position to agent on/in obstacle
|
% find closest position to agent on/in obstacle
|
||||||
cPos = obj.obstacles{jj}.closestToPoint(obj.agents{ii}.pos);
|
cPos = obj.obstacles{jj}.closestToPoint(obj.agents{ii}.lastPos);
|
||||||
|
|
||||||
hObs(ii, jj) = dot(obj.agents{ii}.pos - cPos, obj.agents{ii}.pos - cPos) - obj.agents{ii}.collisionGeometry.radius^2;
|
hObs(ii, jj) = dot(obj.agents{ii}.lastPos - cPos, obj.agents{ii}.lastPos - cPos) - obj.agents{ii}.collisionGeometry.radius^2;
|
||||||
|
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.pos - cPos);
|
A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.lastPos - cPos);
|
||||||
% Floor for single-agent constraint: full correction on one agent, |A| = 2*r_i
|
% Floor for single-agent constraint: full correction on one agent, |A| = 2*r_i
|
||||||
r_i = obj.agents{ii}.collisionGeometry.radius;
|
r_i = obj.agents{ii}.collisionGeometry.radius;
|
||||||
v_max_i = obj.agents{ii}.initialStepSize / obj.timestep;
|
v_max_i = obj.agents{ii}.initialStepSize / obj.timestep;
|
||||||
h_floor_i = -(2 * r_i * v_max_i / obj.barrierGain)^(1 / obj.barrierExponent);
|
hMin = -(2 * r_i * v_max_i / obj.barrierGain)^(1 / obj.barrierExponent);
|
||||||
b(kk) = obj.barrierGain * max(h_floor_i, hObs(ii, jj))^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(hMin, hObs(ii, jj))^obj.barrierExponent;
|
||||||
|
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
obj.barriers(idx:(idx + numel(hObs) - 1), obj.timestepIndex) = reshape(hObs, [], 1);
|
||||||
|
idx = idx + numel(hObs);
|
||||||
|
|
||||||
% Set up domain constraints (walls and ceiling only)
|
% Set up domain constraints (walls and ceiling only)
|
||||||
% Floor constraint is implicit with an obstacle corresponding to the
|
% Floor constraint is implicit with an obstacle corresponding to the
|
||||||
% minimum allowed altitude, but I included it anyways
|
% minimum allowed altitude, but I included it anyways
|
||||||
h_xMin = 0.0; h_xMax = 0.0; h_yMin = 0.0; h_yMax = 0.0; h_zMin = 0.0; h_zMax = 0.0;
|
h_xMin = 0.0; h_xMax = 0.0; h_yMin = 0.0; h_yMax = 0.0; h_zMin = 0.0; h_zMax = 0.0;
|
||||||
for ii = 1:nAgents
|
for ii = 1:nAgents
|
||||||
% X minimum
|
% X minimum
|
||||||
h_xMin = (obj.agents{ii}.pos(1) - obj.domain.minCorner(1)) - obj.agents{ii}.collisionGeometry.radius;
|
h_xMin = (obj.agents{ii}.lastPos(1) - obj.domain.minCorner(1)) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [-1, 0, 0];
|
A(kk, (3 * ii - 2):(3 * ii)) = [-1, 0, 0];
|
||||||
b(kk) = obj.barrierGain * max(0, h_xMin)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_xMin)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
% X maximum
|
% X maximum
|
||||||
h_xMax = (obj.domain.maxCorner(1) - obj.agents{ii}.pos(1)) - obj.agents{ii}.collisionGeometry.radius;
|
h_xMax = (obj.domain.maxCorner(1) - obj.agents{ii}.lastPos(1)) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [1, 0, 0];
|
A(kk, (3 * ii - 2):(3 * ii)) = [1, 0, 0];
|
||||||
b(kk) = obj.barrierGain * max(0, h_xMax)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_xMax)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
% Y minimum
|
% Y minimum
|
||||||
h_yMin = (obj.agents{ii}.pos(2) - obj.domain.minCorner(2)) - obj.agents{ii}.collisionGeometry.radius;
|
h_yMin = (obj.agents{ii}.lastPos(2) - obj.domain.minCorner(2)) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [0, -1, 0];
|
A(kk, (3 * ii - 2):(3 * ii)) = [0, -1, 0];
|
||||||
b(kk) = obj.barrierGain * max(0, h_yMin)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_yMin)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
% Y maximum
|
% Y maximum
|
||||||
h_yMax = (obj.domain.maxCorner(2) - obj.agents{ii}.pos(2)) - obj.agents{ii}.collisionGeometry.radius;
|
h_yMax = (obj.domain.maxCorner(2) - obj.agents{ii}.lastPos(2)) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [0, 1, 0];
|
A(kk, (3 * ii - 2):(3 * ii)) = [0, 1, 0];
|
||||||
b(kk) = obj.barrierGain * max(0, h_yMax)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_yMax)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
% Z minimum — enforce z >= minAlt + radius (not just z >= domain floor + radius)
|
% Z minimum — enforce z >= minAlt + radius (not just z >= domain floor + radius)
|
||||||
h_zMin = (obj.agents{ii}.pos(3) - obj.minAlt) - obj.agents{ii}.collisionGeometry.radius;
|
h_zMin = (obj.agents{ii}.lastPos(3) - obj.minAlt) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [0, 0, -1];
|
A(kk, (3 * ii - 2):(3 * ii)) = [0, 0, -1];
|
||||||
b(kk) = obj.barrierGain * max(0, h_zMin)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_zMin)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
% Z maximum
|
% Z maximum
|
||||||
h_zMax = (obj.domain.maxCorner(3) - obj.agents{ii}.pos(3)) - obj.agents{ii}.collisionGeometry.radius;
|
h_zMax = (obj.domain.maxCorner(3) - obj.agents{ii}.lastPos(3)) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [0, 0, 1];
|
A(kk, (3 * ii - 2):(3 * ii)) = [0, 0, 1];
|
||||||
b(kk) = obj.barrierGain * max(0, h_zMax)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_zMax)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
|
obj.barriers(idx:(idx + 5), obj.timestepIndex) = [h_xMin; h_xMax; h_yMin; h_yMax; h_zMin; h_zMax];
|
||||||
|
idx = idx + 6;
|
||||||
end
|
end
|
||||||
|
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
@@ -133,21 +143,41 @@ function [obj] = constrainMotion(obj)
|
|||||||
for ii = 1:(nAgents - 1)
|
for ii = 1:(nAgents - 1)
|
||||||
for jj = (ii + 1):nAgents
|
for jj = (ii + 1):nAgents
|
||||||
if obj.constraintAdjacencyMatrix(ii, jj)
|
if obj.constraintAdjacencyMatrix(ii, jj)
|
||||||
hComms(ii, jj) = min([obj.agents{ii}.commsGeometry.radius, obj.agents{jj}.commsGeometry.radius])^2 - norm(obj.agents{ii}.pos - obj.agents{jj}.pos)^2;
|
paddingFactor = 0.9; % Barrier at 90% of actual range; real comms still work beyond this
|
||||||
|
r_comms = paddingFactor * min([obj.agents{ii}.commsGeometry.radius, obj.agents{jj}.commsGeometry.radius]);
|
||||||
|
hComms(ii, jj) = r_comms^2 - norm(obj.agents{ii}.lastPos - obj.agents{jj}.lastPos)^2;
|
||||||
|
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = 2 * (obj.agents{ii}.pos - obj.agents{jj}.pos);
|
A(kk, (3 * ii - 2):(3 * ii)) = 2 * (obj.agents{ii}.lastPos - obj.agents{jj}.lastPos);
|
||||||
A(kk, (3 * jj - 2):(3 * jj)) = -A(kk, (3 * ii - 2):(3 * ii));
|
A(kk, (3 * jj - 2):(3 * jj)) = -A(kk, (3 * ii - 2):(3 * ii));
|
||||||
b(kk) = obj.barrierGain * max(0, hComms(ii, jj))^obj.barrierExponent;
|
|
||||||
|
% One-step forward invariance: b = h/dt ensures h cannot
|
||||||
|
% go negative in a single timestep (linear approximation)
|
||||||
|
v_max_ij = max(obj.agents{ii}.initialStepSize, obj.agents{jj}.initialStepSize) / obj.timestep;
|
||||||
|
hMin = -4 * r_comms * v_max_ij * obj.timestep;
|
||||||
|
if norm(A(kk, :)) < 1e-9
|
||||||
|
b(kk) = 0;
|
||||||
|
else
|
||||||
|
b(kk) = max(hMin, hComms(ii, jj)) / obj.timestep;
|
||||||
|
end
|
||||||
|
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
obj.barriers(idx:(idx + length(hComms(triu(true(size(hComms)), 1))) - 1), obj.timestepIndex) = hComms(triu(true(size(hComms)), 1));
|
||||||
|
|
||||||
% Solve QP program generated earlier
|
% Double-integrator: transform QP from velocity to acceleration space.
|
||||||
vhat = reshape(v', 3 * nAgents, 1);
|
% Single-integrator constraint: A * v <= b
|
||||||
|
% Double-integrator: A * a <= (b - A * v_current) / dt
|
||||||
|
if obj.useDoubleIntegrator
|
||||||
|
v_flat = reshape(v', 3 * nAgents, 1);
|
||||||
|
b = (b - A * v_flat) / obj.timestep;
|
||||||
|
end
|
||||||
|
|
||||||
|
% Solve QP: minimize ||u - u_desired||²
|
||||||
|
uhat = reshape(u_desired', 3 * nAgents, 1);
|
||||||
H = 2 * eye(3 * nAgents);
|
H = 2 * eye(3 * nAgents);
|
||||||
f = -2 * vhat;
|
f = -2 * uhat;
|
||||||
|
|
||||||
% Update solution based on constraints
|
% Update solution based on constraints
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
@@ -157,23 +187,36 @@ function [obj] = constrainMotion(obj)
|
|||||||
end
|
end
|
||||||
opt = optimoptions("quadprog", "Display", "off", "Algorithm", "active-set", "UseCodegenSolver", true);
|
opt = optimoptions("quadprog", "Display", "off", "Algorithm", "active-set", "UseCodegenSolver", true);
|
||||||
x0 = zeros(size(H, 1), 1);
|
x0 = zeros(size(H, 1), 1);
|
||||||
[vNew, ~, exitflag, m] = quadprog(H, double(f), A, b, [], [], [], [], x0, opt);
|
[uNew, ~, exitflag] = quadprog(H, double(f), A, b, [], [], [], [], x0, opt);
|
||||||
if coder.target('MATLAB')
|
uNew = reshape(uNew, 3, nAgents)';
|
||||||
assert(exitflag == 1, sprintf("quadprog failure... %s%s", newline, m.message));
|
|
||||||
end
|
|
||||||
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')
|
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
|
||||||
|
uNew = zeros(nAgents, 3);
|
||||||
|
elseif exitflag == 0
|
||||||
|
% Max iterations exceeded: use suboptimal solution already in uNew
|
||||||
|
if coder.target('MATLAB')
|
||||||
|
warning("QP max iterations exceeded, using suboptimal solution.");
|
||||||
|
else
|
||||||
|
fprintf("[constrainMotion] QP max iterations exceeded, using suboptimal solution\n");
|
||||||
end
|
end
|
||||||
vNew = v;
|
|
||||||
end
|
end
|
||||||
|
|
||||||
% Update the "next position" that was previously set by unconstrained
|
% Update agent state using the constrained control input
|
||||||
% GA using the constrained solution produced here
|
for ii = 1:size(uNew, 1)
|
||||||
for ii = 1:size(vNew, 1)
|
if obj.useDoubleIntegrator
|
||||||
obj.agents{ii}.pos = obj.agents{ii}.lastPos + vNew(ii, :) * obj.timestep;
|
% uNew is constrained acceleration
|
||||||
|
obj.agents{ii}.vel = obj.agents{ii}.lastVel + uNew(ii, :) * obj.timestep;
|
||||||
|
obj.agents{ii}.pos = obj.agents{ii}.lastPos + obj.agents{ii}.vel * obj.timestep;
|
||||||
|
else
|
||||||
|
% uNew is constrained velocity
|
||||||
|
obj.agents{ii}.pos = obj.agents{ii}.lastPos + uNew(ii, :) * obj.timestep;
|
||||||
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
% Here we run this at the simulation level, but in reality there is no
|
% Here we run this at the simulation level, but in reality there is no
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, minAlt, timestep, maxIter, obstacles, makePlots, makeVideo)
|
function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, minAlt, timestep, maxIter, obstacles, makePlots, makeVideo, useDoubleIntegrator, dampingCoeff, useFixedTopology)
|
||||||
arguments (Input)
|
arguments (Input)
|
||||||
obj (1, 1) {mustBeA(obj, "miSim")};
|
obj (1, 1) {mustBeA(obj, "miSim")};
|
||||||
domain (1, 1) {mustBeGeometry};
|
domain (1, 1) {mustBeGeometry};
|
||||||
@@ -11,6 +11,9 @@ function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, m
|
|||||||
obstacles (:, 1) cell {mustBeGeometry} = cell(0, 1);
|
obstacles (:, 1) cell {mustBeGeometry} = cell(0, 1);
|
||||||
makePlots(1, 1) logical = true;
|
makePlots(1, 1) logical = true;
|
||||||
makeVideo (1, 1) logical = true;
|
makeVideo (1, 1) logical = true;
|
||||||
|
useDoubleIntegrator (1, 1) logical = false;
|
||||||
|
dampingCoeff (1, 1) double = 2.0;
|
||||||
|
useFixedTopology (1, 1) logical = false;
|
||||||
end
|
end
|
||||||
arguments (Output)
|
arguments (Output)
|
||||||
obj (1, 1) {mustBeA(obj, "miSim")};
|
obj (1, 1) {mustBeA(obj, "miSim")};
|
||||||
@@ -86,9 +89,18 @@ function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, m
|
|||||||
obj.barrierExponent = barrierExponent;
|
obj.barrierExponent = barrierExponent;
|
||||||
obj.minAlt = minAlt;
|
obj.minAlt = minAlt;
|
||||||
|
|
||||||
% Compute adjacency matrix and lesser neighbors
|
% Set dynamics model
|
||||||
|
obj.useDoubleIntegrator = useDoubleIntegrator;
|
||||||
|
obj.dampingCoeff = dampingCoeff;
|
||||||
|
obj.useFixedTopology = useFixedTopology;
|
||||||
|
|
||||||
|
% Compute adjacency matrix and network topology
|
||||||
obj = obj.updateAdjacency();
|
obj = obj.updateAdjacency();
|
||||||
obj = obj.lesserNeighbor();
|
if obj.useFixedTopology
|
||||||
|
obj.constraintAdjacencyMatrix = obj.adjacency;
|
||||||
|
else
|
||||||
|
obj = obj.lesserNeighbor();
|
||||||
|
end
|
||||||
|
|
||||||
% Set up times to iterate over
|
% Set up times to iterate over
|
||||||
obj.times = linspace(0, obj.timestep * obj.maxIter, obj.maxIter+1)';
|
obj.times = linspace(0, obj.timestep * obj.maxIter, obj.maxIter+1)';
|
||||||
@@ -104,11 +116,33 @@ function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, m
|
|||||||
% Create initial partitioning
|
% Create initial partitioning
|
||||||
obj.partitioning = obj.agents{1}.partition(obj.agents, obj.domain.objective);
|
obj.partitioning = obj.agents{1}.partition(obj.agents, obj.domain.objective);
|
||||||
|
|
||||||
|
% Determine number of barrier functions that will be necessary
|
||||||
|
if size(obj.agents, 1) < 2
|
||||||
|
nAAPairs = 0;
|
||||||
|
else
|
||||||
|
nAAPairs = nchoosek(size(obj.agents, 1), 2); % unique agent/agent pairs
|
||||||
|
end
|
||||||
|
nAOPairs = size(obj.agents, 1) * size(obj.obstacles, 1); % unique agent/obstacle pairs
|
||||||
|
nADPairs = size(obj.agents, 1) * 6; % agents x (4 walls + 1 floor + 1 ceiling)
|
||||||
|
nLNAPairs = sum(triu(obj.constraintAdjacencyMatrix, 1), "all");
|
||||||
|
obj.numBarriers = nAAPairs + nAOPairs + nADPairs + nLNAPairs;
|
||||||
|
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
% Initialize variable that will store agent positions for trail plots
|
% Initialize variable that will store agent positions for trail plots
|
||||||
obj.posHist = NaN(size(obj.agents, 1), obj.maxIter + 1, 3);
|
obj.posHist = NaN(size(obj.agents, 1), obj.maxIter + 1, 3);
|
||||||
obj.posHist(1:size(obj.agents, 1), 1, 1:3) = reshape(cell2mat(cellfun(@(x) x.pos, obj.agents, "UniformOutput", false)), size(obj.agents, 1), 1, 3);
|
obj.posHist(1:size(obj.agents, 1), 1, 1:3) = reshape(cell2mat(cellfun(@(x) x.pos, obj.agents, "UniformOutput", false)), size(obj.agents, 1), 1, 3);
|
||||||
|
|
||||||
|
% Initialize velocity history (zeros at t=0, all agents start at rest)
|
||||||
|
obj.velHist = zeros(size(obj.agents, 1), obj.maxIter + 1, 3);
|
||||||
|
|
||||||
|
% Initialize variable that will store barrier function values per timestep for analysis purposes
|
||||||
|
obj.barriers = NaN(obj.numBarriers, size(obj.times, 1));
|
||||||
|
|
||||||
|
% Initialize constraint adjacency history (nAgents x nAgents x nTimesteps)
|
||||||
|
nAgents = size(obj.agents, 1);
|
||||||
|
obj.constraintAdjacencyHist = false(nAgents, nAgents, size(obj.times, 1));
|
||||||
|
obj.constraintAdjacencyHist(:, :, 1) = obj.constraintAdjacencyMatrix;
|
||||||
|
|
||||||
% Set up plots showing initialized state
|
% Set up plots showing initialized state
|
||||||
obj = obj.plot();
|
obj = obj.plot();
|
||||||
|
|
||||||
|
|||||||
@@ -79,6 +79,23 @@ assert(numel(BETA_TILT_VEC) == numAgents, ...
|
|||||||
|
|
||||||
numObstacles = scenario.numObstacles;
|
numObstacles = scenario.numObstacles;
|
||||||
|
|
||||||
|
% Dynamics model (optional columns — backward compatible with older CSVs)
|
||||||
|
if isfield(scenario, 'useDoubleIntegrator')
|
||||||
|
USE_DOUBLE_INTEGRATOR = logical(scenario.useDoubleIntegrator);
|
||||||
|
else
|
||||||
|
USE_DOUBLE_INTEGRATOR = false;
|
||||||
|
end
|
||||||
|
if isfield(scenario, 'dampingCoeff')
|
||||||
|
DAMPING_COEFF = scenario.dampingCoeff;
|
||||||
|
else
|
||||||
|
DAMPING_COEFF = 2.0;
|
||||||
|
end
|
||||||
|
if isfield(scenario, 'useFixedTopology')
|
||||||
|
USE_FIXED_TOPOLOGY = logical(scenario.useFixedTopology);
|
||||||
|
else
|
||||||
|
USE_FIXED_TOPOLOGY = false;
|
||||||
|
end
|
||||||
|
|
||||||
% ---- Build domain --------------------------------------------------------
|
% ---- Build domain --------------------------------------------------------
|
||||||
dom = rectangularPrism;
|
dom = rectangularPrism;
|
||||||
dom = dom.initialize([DOMAIN_MIN; DOMAIN_MAX], REGION_TYPE.DOMAIN, "Guidance Domain");
|
dom = dom.initialize([DOMAIN_MIN; DOMAIN_MAX], REGION_TYPE.DOMAIN, "Guidance Domain");
|
||||||
@@ -124,6 +141,7 @@ end
|
|||||||
|
|
||||||
% ---- Initialise simulation (plots and video disabled) --------------------
|
% ---- Initialise simulation (plots and video disabled) --------------------
|
||||||
obj = obj.initialize(dom, agentList, BARRIER_GAIN, BARRIER_EXPONENT, ...
|
obj = obj.initialize(dom, agentList, BARRIER_GAIN, BARRIER_EXPONENT, ...
|
||||||
MIN_ALT, TIMESTEP, MAX_ITER, obstacleList, false, false);
|
MIN_ALT, TIMESTEP, MAX_ITER, obstacleList, false, false, ...
|
||||||
|
USE_DOUBLE_INTEGRATOR, DAMPING_COEFF, USE_FIXED_TOPOLOGY);
|
||||||
|
|
||||||
end
|
end
|
||||||
|
|||||||
@@ -7,7 +7,6 @@ classdef miSim
|
|||||||
timestepIndex = NaN; % index of the current timestep (useful for time-indexed arrays)
|
timestepIndex = NaN; % index of the current timestep (useful for time-indexed arrays)
|
||||||
maxIter = NaN; % maximum number of simulation iterations
|
maxIter = NaN; % maximum number of simulation iterations
|
||||||
domain;
|
domain;
|
||||||
objective;
|
|
||||||
obstacles; % geometries that define obstacles within the domain
|
obstacles; % geometries that define obstacles within the domain
|
||||||
agents; % agents that move within the domain
|
agents; % agents that move within the domain
|
||||||
adjacency = false(0, 0); % Adjacency matrix representing communications network graph
|
adjacency = false(0, 0); % Adjacency matrix representing communications network graph
|
||||||
@@ -18,8 +17,17 @@ classdef miSim
|
|||||||
barrierGain = NaN; % CBF gain parameter
|
barrierGain = NaN; % CBF gain parameter
|
||||||
barrierExponent = NaN; % CBF exponent parameter
|
barrierExponent = NaN; % CBF exponent parameter
|
||||||
minAlt = 0; % minimum allowable altitude (m)
|
minAlt = 0; % minimum allowable altitude (m)
|
||||||
|
useDoubleIntegrator = false; % false = single-integrator, true = double-integrator dynamics
|
||||||
|
dampingCoeff = 2.0; % velocity-proportional damping for double-integrator mode
|
||||||
|
useFixedTopology = false; % false = lesser neighbor (dynamic), true = fixed initial topology
|
||||||
artifactName = "";
|
artifactName = "";
|
||||||
|
f; % main plotting tiled layout figure
|
||||||
fPerf; % performance plot figure
|
fPerf; % performance plot figure
|
||||||
|
% Indicies for various plot types in the main tiled layout figure
|
||||||
|
spatialPlotIndices = [6, 4, 3, 2];
|
||||||
|
numBarriers = 0; % Number of barrier functions needed
|
||||||
|
barriers = []; % log barrier function values at each timestep for analysis
|
||||||
|
constraintAdjacencyHist = []; % log constraint adjacency matrix at each timestep
|
||||||
end
|
end
|
||||||
|
|
||||||
properties (Access = private)
|
properties (Access = private)
|
||||||
@@ -31,17 +39,16 @@ classdef miSim
|
|||||||
% Plot objects
|
% Plot objects
|
||||||
makePlots = true; % enable/disable simulation plotting (performance implications)
|
makePlots = true; % enable/disable simulation plotting (performance implications)
|
||||||
makeVideo = true; % enable/disable VideoWriter (performance implications)
|
makeVideo = true; % enable/disable VideoWriter (performance implications)
|
||||||
f; % main plotting tiled layout figure
|
|
||||||
connectionsPlot; % objects for lines connecting agents in spatial plots
|
connectionsPlot; % objects for lines connecting agents in spatial plots
|
||||||
graphPlot; % objects for abstract network graph plot
|
graphPlot; % objects for abstract network graph plot
|
||||||
partitionPlot; % objects for partition plot
|
partitionPlot; % objects for partition plot
|
||||||
performancePlot; % objects for sensor performance plot
|
performancePlot; % objects for sensor performance plot
|
||||||
|
|
||||||
posHist; % data for trail plot
|
posHist; % data for trail plot
|
||||||
|
velHist; % velocity history (double-integrator mode)
|
||||||
trailPlot; % objects for agent trail plot
|
trailPlot; % objects for agent trail plot
|
||||||
|
|
||||||
% Indicies for various plot types in the main tiled layout figure
|
% Indicies for various plot types in the main tiled layout figure
|
||||||
spatialPlotIndices = [6, 4, 3, 2];
|
|
||||||
objectivePlotIndices = [6, 4];
|
objectivePlotIndices = [6, 4];
|
||||||
networkGraphIndex = 5;
|
networkGraphIndex = 5;
|
||||||
partitionGraphIndex = 1;
|
partitionGraphIndex = 1;
|
||||||
@@ -60,7 +67,6 @@ classdef miSim
|
|||||||
obj (1, 1) miSim
|
obj (1, 1) miSim
|
||||||
end
|
end
|
||||||
obj.domain = rectangularPrism;
|
obj.domain = rectangularPrism;
|
||||||
obj.objective = sensingObjective;
|
|
||||||
obj.obstacles = {rectangularPrism};
|
obj.obstacles = {rectangularPrism};
|
||||||
obj.agents = {agent};
|
obj.agents = {agent};
|
||||||
end
|
end
|
||||||
|
|||||||
16
@miSim/run.m
16
@miSim/run.m
@@ -30,12 +30,19 @@ function [obj] = run(obj)
|
|||||||
obj.partitioning = obj.agents{1}.partition(obj.agents, obj.domain.objective);
|
obj.partitioning = obj.agents{1}.partition(obj.agents, obj.domain.objective);
|
||||||
|
|
||||||
% Determine desired communications links
|
% Determine desired communications links
|
||||||
obj = obj.lesserNeighbor();
|
if ~obj.useFixedTopology
|
||||||
|
obj = obj.lesserNeighbor();
|
||||||
|
end
|
||||||
|
|
||||||
|
% Log constraint adjacency for this timestep
|
||||||
|
if coder.target('MATLAB')
|
||||||
|
obj.constraintAdjacencyHist(:, :, ii) = obj.constraintAdjacencyMatrix;
|
||||||
|
end
|
||||||
|
|
||||||
% Moving
|
% Moving
|
||||||
% Iterate over agents to simulate their unconstrained motion
|
% Iterate over agents to simulate their unconstrained motion
|
||||||
for jj = 1:size(obj.agents, 1)
|
for jj = 1:size(obj.agents, 1)
|
||||||
obj.agents{jj} = obj.agents{jj}.run(obj.domain, obj.partitioning, obj.timestepIndex, jj, obj.agents);
|
obj.agents{jj} = obj.agents{jj}.run(obj.domain, obj.partitioning, obj.timestepIndex, jj, obj.agents, obj.useDoubleIntegrator, obj.dampingCoeff, obj.timestep);
|
||||||
end
|
end
|
||||||
|
|
||||||
% Adjust motion determined by unconstrained gradient ascent using
|
% Adjust motion determined by unconstrained gradient ascent using
|
||||||
@@ -43,8 +50,9 @@ function [obj] = run(obj)
|
|||||||
obj = constrainMotion(obj);
|
obj = constrainMotion(obj);
|
||||||
|
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
% Update agent position history array
|
% Update agent position and velocity history arrays
|
||||||
obj.posHist(1:size(obj.agents, 1), obj.timestepIndex + 1, 1:3) = reshape(cell2mat(cellfun(@(x) x.pos, obj.agents, "UniformOutput", false)), size(obj.agents, 1), 1, 3);
|
obj.posHist(1:size(obj.agents, 1), obj.timestepIndex + 1, 1:3) = reshape(cell2mat(cellfun(@(x) x.pos, obj.agents, "UniformOutput", false)), size(obj.agents, 1), 1, 3);
|
||||||
|
obj.velHist(1:size(obj.agents, 1), obj.timestepIndex + 1, 1:3) = reshape(cell2mat(cellfun(@(x) x.vel, obj.agents, "UniformOutput", false)), size(obj.agents, 1), 1, 3);
|
||||||
|
|
||||||
% Update total performance
|
% Update total performance
|
||||||
obj.performance = [obj.performance, sum(cellfun(@(x) x.performance(obj.timestepIndex+1), obj.agents))];
|
obj.performance = [obj.performance, sum(cellfun(@(x) x.performance(obj.timestepIndex+1), obj.agents))];
|
||||||
@@ -63,10 +71,12 @@ function [obj] = run(obj)
|
|||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
% Close video
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
if obj.makeVideo
|
if obj.makeVideo
|
||||||
% Close video file
|
% Close video file
|
||||||
v.close();
|
v.close();
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
end
|
end
|
||||||
|
|||||||
@@ -6,25 +6,52 @@ function obj = teardown(obj)
|
|||||||
obj (1, 1) {mustBeA(obj, "miSim")};
|
obj (1, 1) {mustBeA(obj, "miSim")};
|
||||||
end
|
end
|
||||||
|
|
||||||
% Close plots
|
% % Close plots
|
||||||
close(obj.hf);
|
% close(obj.hf);
|
||||||
close(obj.fPerf);
|
% close(obj.fPerf);
|
||||||
close(obj.f);
|
% close(obj.f);
|
||||||
|
|
||||||
|
% Log results into matfile
|
||||||
|
histPath = fullfile(matlab.project.rootProject().RootFolder, "sandbox", strcat(obj.artifactName, "_miSimHist.mat"));
|
||||||
|
out = struct("agent", repmat(struct("pos", [], "vel", [], "perf", [], "sensor", struct("alphaDist", [], "betaDist", [], "alphaTilt", [], "betaTilt", []), "collisionRadius", [], "commsRadius", []), size(obj.agents)), "perf", [], "barriers", [], "useDoubleIntegrator", [], "dampingCoeff", [], "useFixedTopology", []);
|
||||||
|
|
||||||
|
out.perf = obj.performance(1:(end - 1));
|
||||||
|
out.barriers = [zeros(size(obj.barriers(1:end, 1), 1), 1), obj.barriers(1:end, 1:(end - 1))];
|
||||||
|
out.dampingCoeff = obj.dampingCoeff;
|
||||||
|
out.useDoubleIntegrator = obj.useDoubleIntegrator;
|
||||||
|
out.useFixedTopology = obj.useFixedTopology;
|
||||||
|
out.constraintAdjacency = obj.constraintAdjacencyHist(:, :, 1:(end - 1));
|
||||||
|
for ii = 1:size(obj.agents, 1)
|
||||||
|
out.agent(ii).pos = squeeze(obj.posHist(ii, 1:(end - 1), 1:3));
|
||||||
|
out.agent(ii).vel = squeeze(obj.velHist(ii, 1:(end - 1), 1:3));
|
||||||
|
out.agent(ii).perf = obj.agents{ii}.performance(1:(end - 2));
|
||||||
|
out.agent(ii).sensor.alphaDist = obj.agents{ii}.sensorModel.alphaDist;
|
||||||
|
out.agent(ii).sensor.betaDist = obj.agents{ii}.sensorModel.betaDist;
|
||||||
|
out.agent(ii).sensor.alphaTilt = obj.agents{ii}.sensorModel.alphaTilt;
|
||||||
|
out.agent(ii).sensor.betaTilt = obj.agents{ii}.sensorModel.betaTilt;
|
||||||
|
out.agent(ii).collisionRadius = obj.agents{ii}.collisionGeometry.radius;
|
||||||
|
out.agent(ii).commsRadius = obj.agents{ii}.commsGeometry.radius;
|
||||||
|
end
|
||||||
|
|
||||||
|
save(histPath, "out");
|
||||||
|
|
||||||
% reset parameters
|
% reset parameters
|
||||||
obj.timestep = NaN;
|
obj.timestep = NaN;
|
||||||
obj.timestepIndex = NaN;
|
obj.timestepIndex = NaN;
|
||||||
obj.maxIter = NaN;
|
obj.maxIter = NaN;
|
||||||
obj.domain = rectangularPrism;
|
obj.domain = rectangularPrism;
|
||||||
obj.objective = sensingObjective;
|
|
||||||
obj.obstacles = cell(0, 1);
|
obj.obstacles = cell(0, 1);
|
||||||
obj.agents = cell(0, 1);
|
obj.agents = cell(0, 1);
|
||||||
obj.adjacency = NaN;
|
obj.adjacency = NaN;
|
||||||
obj.constraintAdjacencyMatrix = NaN;
|
obj.constraintAdjacencyMatrix = NaN;
|
||||||
|
obj.constraintAdjacencyHist = [];
|
||||||
obj.partitioning = NaN;
|
obj.partitioning = NaN;
|
||||||
obj.performance = 0;
|
obj.performance = 0;
|
||||||
obj.barrierGain = NaN;
|
obj.barrierGain = NaN;
|
||||||
obj.barrierExponent = NaN;
|
obj.barrierExponent = NaN;
|
||||||
|
obj.useDoubleIntegrator = false;
|
||||||
|
obj.dampingCoeff = 2.0;
|
||||||
|
obj.useFixedTopology = false;
|
||||||
obj.artifactName = "";
|
obj.artifactName = "";
|
||||||
|
|
||||||
end
|
end
|
||||||
@@ -7,11 +7,11 @@ function validate(obj)
|
|||||||
|
|
||||||
%% Communications Network Validators
|
%% Communications Network Validators
|
||||||
if max(conncomp(graph(obj.adjacency))) ~= 1
|
if max(conncomp(graph(obj.adjacency))) ~= 1
|
||||||
warning("Network is not connected");
|
error("Network is not connected");
|
||||||
end
|
end
|
||||||
|
|
||||||
if any(obj.adjacency - obj.constraintAdjacencyMatrix < 0, "all")
|
if any(obj.adjacency - obj.constraintAdjacencyMatrix < 0, "all")
|
||||||
warning("Eliminated network connections that were necessary");
|
error("Eliminated network connections that were necessary");
|
||||||
end
|
end
|
||||||
|
|
||||||
%% Obstacle Validators
|
%% Obstacle Validators
|
||||||
@@ -20,10 +20,9 @@ function validate(obj)
|
|||||||
for kk = 1:size(obj.agents, 1)
|
for kk = 1:size(obj.agents, 1)
|
||||||
P = min(max(obj.agents{kk}.pos, obj.obstacles{jj}.minCorner), obj.obstacles{jj}.maxCorner);
|
P = min(max(obj.agents{kk}.pos, obj.obstacles{jj}.minCorner), obj.obstacles{jj}.maxCorner);
|
||||||
d = obj.agents{kk}.pos - P;
|
d = obj.agents{kk}.pos - P;
|
||||||
if dot(d, d) < obj.agents{kk}.collisionGeometry.radius^2
|
if dot(d, d) < obj.agents{kk}.collisionGeometry.radius^2 - 1e-3
|
||||||
warning("%s colliding with %s by %d", obj.agents{kk}.label, obj.obstacles{jj}.label, dot(d, d) - obj.agents{kk}.collisionGeometry.radius^2); % this will cause quadprog to fail
|
error("%s colliding with %s by %d", obj.agents{kk}.label, obj.obstacles{jj}.label, - dot(d, d) + obj.agents{kk}.collisionGeometry.radius^2); % this will cause quadprog to fail
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
end
|
end
|
||||||
|
|||||||
@@ -14,6 +14,8 @@ function writeInits(obj)
|
|||||||
comRanges = cellfun(@(x) x.commsGeometry.radius, obj.agents);
|
comRanges = cellfun(@(x) x.commsGeometry.radius, obj.agents);
|
||||||
initialStepSize = cellfun(@(x) x.initialStepSize, obj.agents);
|
initialStepSize = cellfun(@(x) x.initialStepSize, obj.agents);
|
||||||
pos = cell2mat(cellfun(@(x) x.pos, obj.agents, 'UniformOutput', false));
|
pos = cell2mat(cellfun(@(x) x.pos, obj.agents, 'UniformOutput', false));
|
||||||
|
obsMinCorners = cell2mat(cellfun(@(x) x.minCorner, obj.obstacles, 'UniformOutput', false));
|
||||||
|
obsMaxCorners = cell2mat(cellfun(@(x) x.maxCorner, obj.obstacles, 'UniformOutput', false));
|
||||||
|
|
||||||
|
|
||||||
% Combine with simulation parameters
|
% Combine with simulation parameters
|
||||||
@@ -21,10 +23,13 @@ function writeInits(obj)
|
|||||||
"discretizationStep", obj.domain.objective.discretizationStep, "protectedRange", obj.domain.objective.protectedRange, ...
|
"discretizationStep", obj.domain.objective.discretizationStep, "protectedRange", obj.domain.objective.protectedRange, ...
|
||||||
"sensorPerformanceMinimum", obj.domain.objective.sensorPerformanceMinimum, "initialStepSize", initialStepSize, ...
|
"sensorPerformanceMinimum", obj.domain.objective.sensorPerformanceMinimum, "initialStepSize", initialStepSize, ...
|
||||||
"barrierGain", obj.barrierGain, "barrierExponent", obj.barrierExponent, "numObstacles", size(obj.obstacles, 1), ...
|
"barrierGain", obj.barrierGain, "barrierExponent", obj.barrierExponent, "numObstacles", size(obj.obstacles, 1), ...
|
||||||
"numAgents", size(obj.agents, 1), "collisionRadius", collisionRadii, "comRange", comRanges, "alphaDist", alphaDist, ...
|
"numAgents", size(obj.agents, 1), "collisionRadius", collisionRadii, "comRange", comRanges, ...
|
||||||
"betaDist", betaDist, "alphaTilt", alphaTilt, "betaTilt", betaTilt, ...
|
"useDoubleIntegrator", obj.useDoubleIntegrator, "dampingCoeff", obj.dampingCoeff, ...
|
||||||
|
"alphaDist", alphaDist, "betaDist", betaDist, "alphaTilt", alphaTilt, "betaTilt", betaTilt, ...
|
||||||
... % ^^^ PARAMETERS ^^^ | vvv STATES vvv
|
... % ^^^ PARAMETERS ^^^ | vvv STATES vvv
|
||||||
"pos", pos);
|
"pos", pos, "objectivePos", obj.domain.objective.groundPos, "objectiveSigma", obj.domain.objective.objectiveSigma, ...
|
||||||
|
"obsMinCorners", obsMinCorners, "obsMaxCorners", obsMaxCorners, ...
|
||||||
|
"objectiveIntegral", sum(obj.domain.objective.values(:)));
|
||||||
|
|
||||||
% Save all parameters to output file
|
% Save all parameters to output file
|
||||||
initsFile = strcat(obj.artifactName, "_miSimInits");
|
initsFile = strcat(obj.artifactName, "_miSimInits");
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
function obj = initialize(obj, objectiveFunction, domain, discretizationStep, protectedRange, sensorPerformanceMinimum)
|
function obj = initialize(obj, objectiveFunction, domain, discretizationStep, protectedRange, sensorPerformanceMinimum, objectiveMu, objectiveSigma)
|
||||||
arguments (Input)
|
arguments (Input)
|
||||||
obj (1,1) {mustBeA(obj, "sensingObjective")};
|
obj (1,1) {mustBeA(obj, "sensingObjective")};
|
||||||
objectiveFunction (1, 1) {mustBeA(objectiveFunction, "function_handle")};
|
objectiveFunction (1, 1) {mustBeA(objectiveFunction, "function_handle")};
|
||||||
@@ -6,6 +6,8 @@ function obj = initialize(obj, objectiveFunction, domain, discretizationStep, pr
|
|||||||
discretizationStep (1, 1) double = 1;
|
discretizationStep (1, 1) double = 1;
|
||||||
protectedRange (1, 1) double = 1;
|
protectedRange (1, 1) double = 1;
|
||||||
sensorPerformanceMinimum (1, 1) double = 1e-6;
|
sensorPerformanceMinimum (1, 1) double = 1e-6;
|
||||||
|
objectiveMu (:, 2) double = NaN(1, 2);
|
||||||
|
objectiveSigma (:, 2, 2) double = NaN(1, 2, 2);
|
||||||
end
|
end
|
||||||
arguments (Output)
|
arguments (Output)
|
||||||
obj (1,1) {mustBeA(obj, "sensingObjective")};
|
obj (1,1) {mustBeA(obj, "sensingObjective")};
|
||||||
@@ -37,8 +39,13 @@ function obj = initialize(obj, objectiveFunction, domain, discretizationStep, pr
|
|||||||
|
|
||||||
% store ground position
|
% store ground position
|
||||||
idx = obj.values == 1;
|
idx = obj.values == 1;
|
||||||
obj.groundPos = [obj.X(idx), obj.Y(idx)];
|
if any(isnan(objectiveMu))
|
||||||
obj.groundPos = obj.groundPos(1, 1:2); % for safety, in case 2 points are maximal (somehow)
|
obj.groundPos = [obj.X(idx), obj.Y(idx)];
|
||||||
|
obj.groundPos = obj.groundPos(1, 1:2); % for safety, in case 2 points are maximal (somehow)
|
||||||
|
else
|
||||||
|
obj.groundPos = objectiveMu;
|
||||||
|
end
|
||||||
|
obj.objectiveSigma = objectiveSigma;
|
||||||
|
|
||||||
assert(domain.distance([obj.groundPos, domain.center(3)]) > protectedRange, "Domain is crowding the sensing objective")
|
assert(domain.distance([obj.groundPos, ones(size(obj.groundPos, 1), 1) .* domain.center(3)]) > protectedRange, "Domain is crowding the sensing objective")
|
||||||
end
|
end
|
||||||
@@ -11,7 +11,7 @@ function obj = initializeRandomMvnpdf(obj, domain, discretizationStep, protected
|
|||||||
|
|
||||||
% Set random objective position
|
% Set random objective position
|
||||||
mu = domain.minCorner;
|
mu = domain.minCorner;
|
||||||
while domain.distance(mu) < protectedRange
|
while domain.distance(mu) < protectedRange * 1.01
|
||||||
mu = domain.random();
|
mu = domain.random();
|
||||||
end
|
end
|
||||||
|
|
||||||
|
|||||||
@@ -2,7 +2,8 @@ classdef sensingObjective
|
|||||||
% Sensing objective definition parent class
|
% Sensing objective definition parent class
|
||||||
properties (SetAccess = private, GetAccess = public)
|
properties (SetAccess = private, GetAccess = public)
|
||||||
label = "";
|
label = "";
|
||||||
groundPos = [NaN, NaN];
|
groundPos = NaN(1, 2);
|
||||||
|
objectiveSigma = NaN(1, 2, 2);
|
||||||
discretizationStep = NaN;
|
discretizationStep = NaN;
|
||||||
X = [];
|
X = [];
|
||||||
Y = [];
|
Y = [];
|
||||||
|
|||||||
Submodule aerpaw/aerpawlib deleted from 705fc699ef
@@ -46,8 +46,9 @@ class MessageType(IntEnum):
|
|||||||
POSITION = 8
|
POSITION = 8
|
||||||
|
|
||||||
|
|
||||||
AERPAW_DIR = Path(__file__).parent.parent
|
AERPAW_DIR = Path('/root/miSim/aerpaw')
|
||||||
CONFIG_FILE = AERPAW_DIR / "config" / "client.yaml"
|
CONFIG_FILE = Path(os.environ.get('AERPAW_CLIENT_CONFIG',
|
||||||
|
AERPAW_DIR / "config" / "client.yaml"))
|
||||||
|
|
||||||
|
|
||||||
def load_config():
|
def load_config():
|
||||||
@@ -115,8 +116,9 @@ def _gps_log_row(vehicle, line_num, writer):
|
|||||||
|
|
||||||
async def _gps_log_loop(drone):
|
async def _gps_log_loop(drone):
|
||||||
"""Background async task that logs GPS data at 1Hz."""
|
"""Background async task that logs GPS data at 1Hz."""
|
||||||
host = platform.node()
|
results_dir = os.environ.get('RESULTS_DIR', '/root/Results')
|
||||||
filename = f"/root/Results/GPS_DATA_{host}_{datetime.datetime.now().strftime('%Y-%m-%d_%H:%M:%S')}.csv"
|
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}")
|
print(f"[UAV] GPS logging to {filename}")
|
||||||
line_num = 1
|
line_num = 1
|
||||||
try:
|
try:
|
||||||
|
|||||||
@@ -1,9 +1,19 @@
|
|||||||
# AERPAW UAV (Client) Configuration
|
# 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)
|
# ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
|
||||||
origin:
|
origin:
|
||||||
lat: 35.72550610629396
|
lat: 35.72595214250436
|
||||||
lon: -78.70019657805574
|
lon: -78.69917609299937
|
||||||
alt: 0.0 # Alt=0 means ENU z directly becomes target altitude above home
|
alt: 0.0 # Alt=0 means ENU z directly becomes target altitude above home
|
||||||
# Environment-specific settings
|
# Environment-specific settings
|
||||||
environments:
|
environments:
|
||||||
@@ -22,7 +32,7 @@ environments:
|
|||||||
mavlink:
|
mavlink:
|
||||||
ip: "192.168.32.26"
|
ip: "192.168.32.26"
|
||||||
port: 14550
|
port: 14550
|
||||||
# Controller runs on host machine (192.168.122.1 from E-VM perspective)
|
# Controller runs on host machine (192.168.109.1 from E-VM perspective)
|
||||||
controller:
|
controller:
|
||||||
ip: "192.168.122.1"
|
ip: "192.168.109.1"
|
||||||
port: 5000
|
port: 5000
|
||||||
38
aerpaw/config/client2.yaml
Normal file
38
aerpaw/config/client2.yaml
Normal 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.72595214250436
|
||||||
|
lon: -78.69917609299937
|
||||||
|
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.109.1 from E-VM perspective)
|
||||||
|
controller:
|
||||||
|
ip: "192.168.109.1"
|
||||||
|
port: 5000
|
||||||
@@ -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
|
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
|
||||||
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"
|
1, 150, 30.0, 0.1, 2.0, 1, 1, 1, "5.0, 5.0", "25.0, 25.0", "80.0, 80.0", "0.25, 0.25", "5.0, 5.0", "0.1, 0.1", "0.0, 0.0, 0.0", "80.0, 80.0, 80.0", "55.0, 55.0", "40, 25, 25, 40", 0.15, "15.0, 10.0, 40.0, 5.0, 10.0, 45.0", 1, "1.0, 25.0, 0.0", "30.0, 30.0, 50.0", 1, 2.0, 1
|
||||||
|
@@ -128,6 +128,16 @@
|
|||||||
<Size type="coderapp.internal.codertype.Dimension"/>
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
<Size type="coderapp.internal.codertype.Dimension"/>
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
</Types>
|
</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 id="27" type="coderapp.internal.codertype.PrimitiveType">
|
||||||
|
<ClassName>int32</ClassName>
|
||||||
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
|
</Types>
|
||||||
</Types>
|
</Types>
|
||||||
</coderapp.internal.interface.project.Interface>
|
</coderapp.internal.interface.project.Interface>
|
||||||
</MF0>
|
</MF0>
|
||||||
@@ -519,575 +529,569 @@
|
|||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="65" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="65" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="66" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="66" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="67" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="67" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="68" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="68" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="69" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="69" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="70" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="70" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="71" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="71" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="72" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="72" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="73" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="73" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="74" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="74" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="75" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="75" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="76" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="76" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="77" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="77" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="78" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="78" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="79" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="79" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="80" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="80" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="81" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="81" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="82" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="82" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="83" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="83" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="84" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="84" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="85" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="85" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="86" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="86" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="87" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="87" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="88" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="88" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="89" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="89" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="90" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="90" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="91" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="91" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="92" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="92" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="93" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="93" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="94" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="94" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="95" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="95" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="96" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="96" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="97" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="97" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="98" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="98" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="99" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="99" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="100" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="100" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="101" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="101" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="102" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="102" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="103" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="103" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="104" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="104" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="105" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="105" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="106" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="106" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="107" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="107" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="108" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="108" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="109" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="109" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="110" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="110" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="111" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="111" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="112" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="112" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="113" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="113" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="114" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="114" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="115" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="115" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="116" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="116" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="117" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="117" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="118" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="118" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="119" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="119" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="120" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="120" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="121" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="121" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="122" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="122" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="123" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="123" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="124" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="124" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="125" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="125" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="126" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="126" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="127" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="127" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="128" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="128" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="129" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="129" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="130" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="130" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="131" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="131" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="132" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="132" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="133" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="133" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="134" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="134" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="135" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="135" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="136" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="136" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="137" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="137" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="138" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="138" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="139" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="139" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="140" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="140" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="141" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="141" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="142" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="142" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="143" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="143" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="144" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="144" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="145" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="145" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="146" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="146" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="147" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="147" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="148" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="148" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="149" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="149" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="150" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="150" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="151" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="151" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="152" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="152" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="153" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="153" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="154" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="154" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="155" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="155" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="156" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="156" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="157" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="157" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<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>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="158" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<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">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/examples/main.cpp</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/examples/main.cpp</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</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">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/examples/main.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/examples/main.h</Path>
|
||||||
</File>
|
</File>
|
||||||
@@ -1095,7 +1099,7 @@
|
|||||||
</Artifacts>
|
</Artifacts>
|
||||||
<BuildFolder type="coderapp.internal.util.mfz.FileSpec"/>
|
<BuildFolder type="coderapp.internal.util.mfz.FileSpec"/>
|
||||||
<Success>true</Success>
|
<Success>true</Success>
|
||||||
<Timestamp>2026-03-03T15:54:20</Timestamp>
|
<Timestamp>2026-03-11T17:11:03</Timestamp>
|
||||||
</MainBuildResult>
|
</MainBuildResult>
|
||||||
</coderapp.internal.mlc.mfz.MatlabCoderProjectState>
|
</coderapp.internal.mlc.mfz.MatlabCoderProjectState>
|
||||||
</MF0>
|
</MF0>
|
||||||
|
|||||||
@@ -135,7 +135,7 @@ if isInit
|
|||||||
|
|
||||||
% --- Build obstacle list from flat arrays ---
|
% --- Build obstacle list from flat arrays ---
|
||||||
coder.varsize('obstacleList', [8, 1], [1, 0]);
|
coder.varsize('obstacleList', [8, 1], [1, 0]);
|
||||||
obstacleList = cell(int32(0), 1);
|
obstacleList = repmat({rectangularPrism}, numObstacles, 1);
|
||||||
for ii = 1:numObstacles
|
for ii = 1:numObstacles
|
||||||
obs = rectangularPrism;
|
obs = rectangularPrism;
|
||||||
obs = obs.initialize([obstacleMin(ii, :); obstacleMax(ii, :)], ...
|
obs = obs.initialize([obstacleMin(ii, :); obstacleMax(ii, :)], ...
|
||||||
|
|||||||
@@ -1,12 +1,17 @@
|
|||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include "controller.h"
|
#include "controller.h"
|
||||||
#include "controller_impl.h" // TCP implementation header
|
#include "controller_impl.h" // TCP implementation header
|
||||||
|
|
||||||
int main() {
|
int main() {
|
||||||
// Number of clients to handle
|
// Derive numClients from initialPositions in scenario.csv
|
||||||
int numClients = 2; // for now
|
double targets[MAX_CLIENTS_PER_PARAM * 3];
|
||||||
|
int numClients = loadInitialPositions("config/scenario.csv",
|
||||||
std::cout << "Initializing TCP server...\n";
|
targets, MAX_CLIENTS_PER_PARAM);
|
||||||
|
if (numClients < 1) {
|
||||||
|
std::cerr << "Failed to parse numClients from scenario.csv\n";
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
std::cout << "Parsed " << numClients << " UAV(s) from scenario.csv\n";
|
||||||
|
|
||||||
// Call MATLAB-generated server function
|
// Call MATLAB-generated server function
|
||||||
controller(numClients);
|
controller(numClients);
|
||||||
|
|||||||
554
aerpaw/radio/CSwSNRRX.py
Normal file
554
aerpaw/radio/CSwSNRRX.py
Normal file
File diff suppressed because one or more lines are too long
336
aerpaw/radio/CSwSNRTX.py
Normal file
336
aerpaw/radio/CSwSNRTX.py
Normal 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)
|
||||||
|
|
||||||
|
|
||||||
23
aerpaw/radio/startchannelsounderRXGRC.sh
Executable file
23
aerpaw/radio/startchannelsounderRXGRC.sh
Executable 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 "$@"
|
||||||
23
aerpaw/radio/startchannelsounderTXGRC.sh
Executable file
23
aerpaw/radio/startchannelsounderTXGRC.sh
Executable 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 "$@"
|
||||||
15
aerpaw/radio/updateScripts.sh
Executable file
15
aerpaw/radio/updateScripts.sh
Executable file
@@ -0,0 +1,15 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
|
||||||
|
# Drop in replacements for channel sounder scripts
|
||||||
|
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/.
|
||||||
|
|
||||||
|
# Replace start scripts
|
||||||
|
cp ../scripts/startexperiment.sh /root/.
|
||||||
|
cp ../scripts/startRadio.sh /root/Profiles/ProfileScripts/Radio/.
|
||||||
|
cp ../scripts/startVehicle.sh /root/Profiles/ProfileScripts/Vehicle/.
|
||||||
|
|
||||||
|
echo "REMEMBER! Manually edit startexperiment.sh to point to the correct client.yaml"
|
||||||
|
echo "REMEMBER! Manually copy startexperiment_controller.sh to startexperiment.sh on the fixed node"
|
||||||
@@ -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");
|
|
||||||
97
aerpaw/results/plotGpsLogs.m
Normal file
97
aerpaw/results/plotGpsLogs.m
Normal 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
|
||||||
84
aerpaw/results/plotRadioLogs.m
Normal file
84
aerpaw/results/plotRadioLogs.m
Normal file
@@ -0,0 +1,84 @@
|
|||||||
|
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
|
||||||
|
|
||||||
|
% Compute path loss from Power (post-processing)
|
||||||
|
% Power = 20*log10(peak_mag) - rxGain; path loss = txGain - rxGain - Power
|
||||||
|
txGain_dB = 76; % from startchannelsounderTXGRC.sh GAIN_TX
|
||||||
|
rxGain_dB = 30; % from startchannelsounderRXGRC.sh GAIN_RX
|
||||||
|
for ii = 1:numel(R)
|
||||||
|
R{ii}.PathLoss = txGain_dB - rxGain_dB - R{ii}.Power;
|
||||||
|
R{ii}.FreqOffset = R{ii}.FreqOffset / 1e6; % Hz to MHz
|
||||||
|
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", "PathLoss", "NoiseFloor", "FreqOffset"];
|
||||||
|
yLabels = ["SNR (dB)", "Power (dB)", "Quality", "Path Loss (dB)", "Noise Floor (dB)", "Freq Offset (MHz)"];
|
||||||
|
|
||||||
|
f = figure;
|
||||||
|
tl = tiledlayout(numel(metricNames), 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
|
||||||
@@ -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
|
|
||||||
32
aerpaw/results/readGpsLogs.m
Normal file
32
aerpaw/results/readGpsLogs.m
Normal 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
|
||||||
67
aerpaw/results/readRadioLogs.m
Normal file
67
aerpaw/results/readRadioLogs.m
Normal file
@@ -0,0 +1,67 @@
|
|||||||
|
function R = readRadioLogs(logPath)
|
||||||
|
arguments (Input)
|
||||||
|
logPath (1, 1) string {isfolder(logPath)};
|
||||||
|
end
|
||||||
|
|
||||||
|
arguments (Output)
|
||||||
|
R (:, 8) 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", "noisefloor", "freqoffset"];
|
||||||
|
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), zeros(0,1), zeros(0,1), ...
|
||||||
|
'VariableNames', ["Timestamp", "TxUAVID", "RxUAVID", "SNR", "Power", "Quality", "NoiseFloor", "FreqOffset"]);
|
||||||
|
|
||||||
|
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), NaN(n,1), NaN(n,1), ...
|
||||||
|
'VariableNames', ["Timestamp", "TxUAVID", "RxUAVID", "SNR", "Power", "Quality", "NoiseFloor", "FreqOffset"]);
|
||||||
|
|
||||||
|
switch metric
|
||||||
|
case "snr", t.SNR = val;
|
||||||
|
case "power", t.Power = val;
|
||||||
|
case "quality", t.Quality = val;
|
||||||
|
case "noisefloor", t.NoiseFloor = val;
|
||||||
|
case "freqoffset", t.FreqOffset = 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
|
||||||
68
aerpaw/results/resultsAnalysis.m
Normal file
68
aerpaw/results/resultsAnalysis.m
Normal file
@@ -0,0 +1,68 @@
|
|||||||
|
%% Plot AERPAW logs (trajectory, radio)
|
||||||
|
resultsPath = fullfile(matlab.project.rootProject().RootFolder, "sandbox", "two_around_wall"); % 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
|
||||||
@@ -3,13 +3,13 @@
|
|||||||
# Launches UAV client with environment-specific configuration
|
# Launches UAV client with environment-specific configuration
|
||||||
#
|
#
|
||||||
# Usage:
|
# Usage:
|
||||||
# ./run_uav.sh local # Use local/simulation configuration
|
# ./run_uav.sh local # defaults to config/client.yaml
|
||||||
# ./run_uav.sh testbed # Use AERPAW testbed configuration
|
# ./run_uav.sh testbed config/client2.yaml # use a specific config file
|
||||||
|
|
||||||
set -e
|
set -e
|
||||||
|
|
||||||
# Change to script directory
|
# Change to aerpaw directory
|
||||||
cd "$(dirname "$0")"
|
cd /root/miSim/aerpaw
|
||||||
|
|
||||||
# Activate venv if it exists
|
# Activate venv if it exists
|
||||||
if [ -d "venv" ]; then
|
if [ -d "venv" ]; then
|
||||||
@@ -23,22 +23,33 @@ elif [ "$1" = "local" ]; then
|
|||||||
ENV="local"
|
ENV="local"
|
||||||
else
|
else
|
||||||
echo "Error: Environment not specified."
|
echo "Error: Environment not specified."
|
||||||
echo "Usage: $0 [local|testbed]"
|
echo "Usage: $0 [local|testbed] [config_file]"
|
||||||
echo ""
|
echo ""
|
||||||
echo " local - Use local/simulation configuration"
|
echo " local - Use local/simulation configuration"
|
||||||
echo " testbed - Use AERPAW testbed 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: 2nd argument > AERPAW_CLIENT_CONFIG env var > default
|
||||||
|
CONFIG_FILE="${2:-${AERPAW_CLIENT_CONFIG:-config/client.yaml}}"
|
||||||
|
if [ ! -f "$CONFIG_FILE" ]; then
|
||||||
|
echo "Error: Config file not found: $CONFIG_FILE"
|
||||||
exit 1
|
exit 1
|
||||||
fi
|
fi
|
||||||
|
|
||||||
echo "[run_uav] Environment: $ENV"
|
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_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 "
|
CONN=$(python3 -c "
|
||||||
import yaml
|
import yaml
|
||||||
with open('config/client.yaml') as f:
|
with open('$CONFIG_FILE') as f:
|
||||||
cfg = yaml.safe_load(f)
|
cfg = yaml.safe_load(f)
|
||||||
env = cfg['environments']['$ENV']['mavlink']
|
env = cfg['environments']['$ENV']['mavlink']
|
||||||
print(f\"udp:{env['ip']}:{env['port']}\")
|
print(f\"udp:{env['ip']}:{env['port']}\")
|
||||||
@@ -48,7 +59,7 @@ echo "[run_uav] MAVLink connection: $CONN"
|
|||||||
|
|
||||||
# Run via aerpawlib
|
# Run via aerpawlib
|
||||||
echo "[run_uav] Starting UAV runner..."
|
echo "[run_uav] Starting UAV runner..."
|
||||||
python3 -m aerpawlib \
|
python3 -u -m aerpawlib \
|
||||||
--script client.uav_runner \
|
--script client.uav_runner \
|
||||||
--conn "$CONN" \
|
--conn "$CONN" \
|
||||||
--vehicle drone
|
--vehicle drone
|
||||||
100
aerpaw/scripts/startRadio.sh
Executable file
100
aerpaw/scripts/startRadio.sh
Executable file
@@ -0,0 +1,100 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
|
||||||
|
# Derive number of UAVs from scenario.csv
|
||||||
|
NUM_UAVS=$(python3 -c "
|
||||||
|
import csv, os
|
||||||
|
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')
|
||||||
|
vals = [v.strip() for v in row[col].strip().split(',') if v.strip()]
|
||||||
|
print(len(vals) // 3)
|
||||||
|
" 2>/dev/null || echo 0)
|
||||||
|
|
||||||
|
cd $PROFILE_DIR"/ProfileScripts/Radio/Helpers"
|
||||||
|
|
||||||
|
if [ "$NUM_UAVS" -eq 2 ]; then
|
||||||
|
# Direct 1-to-1 mode: UAV 0 = TX only, UAV 1 = RX only
|
||||||
|
echo "[Radio] 2-UAV direct mode: UAV_ID=$UAV_ID"
|
||||||
|
|
||||||
|
if [ "$UAV_ID" -eq 0 ]; then
|
||||||
|
# TX only (--num-uavs 1 disables TDM muting)
|
||||||
|
screen -S txGRC -dm \
|
||||||
|
bash -c "stdbuf -oL -eL ./startchannelsounderTXGRC.sh --num-uavs 1 \
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_radio_channelsoundertxgrc_log.txt"
|
||||||
|
else
|
||||||
|
# RX only (--num-uavs 1 disables TDM tagging)
|
||||||
|
screen -S rxGRC -dm \
|
||||||
|
bash -c "stdbuf -oL -eL ./startchannelsounderRXGRC.sh --num-uavs 1 \
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_radio_channelsounderrxgrc_log.txt"
|
||||||
|
|
||||||
|
screen -S power -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/Power\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_power_log.txt"
|
||||||
|
|
||||||
|
screen -S quality -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/Quality\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_quality_log.txt"
|
||||||
|
|
||||||
|
screen -S snr -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/SNR\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_snr_log.txt"
|
||||||
|
|
||||||
|
screen -S noisefloor -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/NoiseFloor\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_noisefloor_log.txt"
|
||||||
|
|
||||||
|
screen -S freqoffset -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/FreqOffset\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_freqoffset_log.txt"
|
||||||
|
fi
|
||||||
|
else
|
||||||
|
# 3+ UAVs: full TDM mode — every node runs both TX and RX
|
||||||
|
echo "[Radio] TDM mode: $NUM_UAVS UAVs, UAV_ID=$UAV_ID"
|
||||||
|
|
||||||
|
screen -S rxGRC -dm \
|
||||||
|
bash -c "stdbuf -oL -eL ./startchannelsounderRXGRC.sh \
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_radio_channelsounderrxgrc_log.txt"
|
||||||
|
|
||||||
|
screen -S power -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/Power\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_power_log.txt"
|
||||||
|
|
||||||
|
screen -S quality -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/Quality\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_quality_log.txt"
|
||||||
|
|
||||||
|
screen -S snr -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/SNR\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_snr_log.txt"
|
||||||
|
|
||||||
|
screen -S noisefloor -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/NoiseFloor\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_noisefloor_log.txt"
|
||||||
|
|
||||||
|
screen -S freqoffset -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/FreqOffset\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_freqoffset_log.txt"
|
||||||
|
|
||||||
|
screen -S txGRC -dm \
|
||||||
|
bash -c "stdbuf -oL -eL ./startchannelsounderTXGRC.sh \
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_radio_channelsoundertxgrc_log.txt"
|
||||||
|
fi
|
||||||
|
|
||||||
|
cd -
|
||||||
30
aerpaw/scripts/startVehicle.sh
Executable file
30
aerpaw/scripts/startVehicle.sh
Executable file
@@ -0,0 +1,30 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
|
||||||
|
### Sample GPS logger portion
|
||||||
|
# use vehicle type generic to skip the arming requirement
|
||||||
|
export VEHICLE_TYPE="${VEHICLE_TYPE:-generic}"
|
||||||
|
|
||||||
|
# GPS Logger sample application (this does not move the vehicle)
|
||||||
|
|
||||||
|
#cd $PROFILE_DIR"/ProfileScripts/Vehicle/Helpers"
|
||||||
|
#
|
||||||
|
#screen -S vehicle -dm \
|
||||||
|
# bash -c "stdbuf -oL -eL ./gpsLoggerHelper.sh \
|
||||||
|
# 2> >(ts $TS_FORMAT >> $RESULTS_DIR/${LOG_PREFIX}_vehicle_log_err.txt) \
|
||||||
|
# | ts $TS_FORMAT \
|
||||||
|
# | tee $RESULTS_DIR/$LOG_PREFIX\_vehicle_log.txt"
|
||||||
|
#
|
||||||
|
#cd -
|
||||||
|
|
||||||
|
### Actual control portion (custom)
|
||||||
|
export VEHICLE_TYPE="${VEHICLE_TYPE:-drone}" # out of rover, drone, generic
|
||||||
|
|
||||||
|
cd /root/miSim/aerpaw
|
||||||
|
|
||||||
|
# Use screen/ts/tee aerpawism from sample script
|
||||||
|
screen -S vehicle -dm \
|
||||||
|
bash -c "stdbuf -oL -eL ./run_uav.sh testbed \
|
||||||
|
| ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_vehicle_log.txt"
|
||||||
|
|
||||||
|
cd -
|
||||||
11
aerpaw/scripts/startVehicle_controller.sh
Executable file
11
aerpaw/scripts/startVehicle_controller.sh
Executable file
@@ -0,0 +1,11 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
|
||||||
|
cd /root/miSim/aerpaw
|
||||||
|
|
||||||
|
# Compile controller
|
||||||
|
/bin/bash compile.sh
|
||||||
|
|
||||||
|
# Run controller
|
||||||
|
./build/controller_app
|
||||||
|
|
||||||
|
cd -
|
||||||
50
aerpaw/scripts/startexperiment.sh
Executable file
50
aerpaw/scripts/startexperiment.sh
Executable file
@@ -0,0 +1,50 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
/root/stopexperiment.sh
|
||||||
|
|
||||||
|
source /root/.ap-set-experiment-env.sh
|
||||||
|
source /root/.bashrc
|
||||||
|
|
||||||
|
# set path to client config YAML
|
||||||
|
export AERPAW_CLIENT_CONFIG=/root/miSim/aerpaw/config/client1.yaml
|
||||||
|
|
||||||
|
export AERPAW_REPO=${AERPAW_REPO:-/root/AERPAW-Dev}
|
||||||
|
export AERPAW_PYTHON=${AERPAW_PYTHON:-python3}
|
||||||
|
export PYTHONPATH=/usr/local/lib/python3/dist-packages/
|
||||||
|
export EXP_NUMBER=${EXP_NUMBER:-1}
|
||||||
|
|
||||||
|
if [ "$AP_EXPENV_THIS_CONTAINER_NODE_VEHICLE" == "vehicle_uav" ]; then
|
||||||
|
export VEHICLE_TYPE=drone
|
||||||
|
elif [ "$AP_EXPENV_THIS_CONTAINER_NODE_VEHICLE" == "vehicle_ugv" ]; then
|
||||||
|
export VEHICLE_TYPE=rover
|
||||||
|
else
|
||||||
|
export VEHICLE_TYPE=none
|
||||||
|
fi
|
||||||
|
|
||||||
|
if [ "$AP_EXPENV_SESSION_ENV" == "Virtual" ]; then
|
||||||
|
export LAUNCH_MODE=EMULATION
|
||||||
|
elif [ "$AP_EXPENV_SESSION_ENV" == "Testbed" ]; then
|
||||||
|
export LAUNCH_MODE=TESTBED
|
||||||
|
else
|
||||||
|
export LAUNCH_MODE=none
|
||||||
|
fi
|
||||||
|
|
||||||
|
# prepare results directory
|
||||||
|
export UAV_ID=$(python3 -c "import yaml; print(yaml.safe_load(open('$AERPAW_CLIENT_CONFIG'))['uav_id'])")
|
||||||
|
export RESULTS_DIR_TIMESTAMP=$(date +%Y-%m-%d_%H_%M_%S)
|
||||||
|
export RESULTS_DIR="/root/Results/uav${UAV_ID}_${RESULTS_DIR_TIMESTAMP}"
|
||||||
|
mkdir -p "$RESULTS_DIR"
|
||||||
|
|
||||||
|
export TS_FORMAT="${TS_FORMAT:-'[%Y-%m-%d %H:%M:%.S]'}"
|
||||||
|
export LOG_PREFIX="$(date +%Y-%m-%d_%H_%M_%S)"
|
||||||
|
|
||||||
|
export TX_FREQ=3.32e9
|
||||||
|
export RX_FREQ=3.32e9
|
||||||
|
|
||||||
|
export PROFILE_DIR=$AERPAW_REPO"/AHN/E-VM/Profile_software"
|
||||||
|
cd $PROFILE_DIR"/ProfileScripts"
|
||||||
|
|
||||||
|
./Radio/startRadio.sh
|
||||||
|
#./Traffic/startTraffic.sh
|
||||||
|
./Vehicle/startVehicle.sh
|
||||||
|
|
||||||
|
schedule_stop.sh 30
|
||||||
47
aerpaw/scripts/startexperiment_controller.sh
Executable file
47
aerpaw/scripts/startexperiment_controller.sh
Executable file
@@ -0,0 +1,47 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
/root/stopexperiment.sh
|
||||||
|
|
||||||
|
source /root/.ap-set-experiment-env.sh
|
||||||
|
source /root/.bashrc
|
||||||
|
|
||||||
|
export AERPAW_REPO=${AERPAW_REPO:-/root/AERPAW-Dev}
|
||||||
|
export AERPAW_PYTHON=${AERPAW_PYTHON:-python3}
|
||||||
|
export PYTHONPATH=/usr/local/lib/python3/dist-packages/
|
||||||
|
export EXP_NUMBER=${EXP_NUMBER:-1}
|
||||||
|
|
||||||
|
if [ "$AP_EXPENV_THIS_CONTAINER_NODE_VEHICLE" == "vehicle_uav" ]; then
|
||||||
|
export VEHICLE_TYPE=drone
|
||||||
|
elif [ "$AP_EXPENV_THIS_CONTAINER_NODE_VEHICLE" == "vehicle_ugv" ]; then
|
||||||
|
export VEHICLE_TYPE=rover
|
||||||
|
else
|
||||||
|
export VEHICLE_TYPE=none
|
||||||
|
fi
|
||||||
|
|
||||||
|
if [ "$AP_EXPENV_SESSION_ENV" == "Virtual" ]; then
|
||||||
|
export LAUNCH_MODE=EMULATION
|
||||||
|
elif [ "$AP_EXPENV_SESSION_ENV" == "Testbed" ]; then
|
||||||
|
export LAUNCH_MODE=TESTBED
|
||||||
|
else
|
||||||
|
export LAUNCH_MODE=none
|
||||||
|
fi
|
||||||
|
|
||||||
|
# prepare results directory
|
||||||
|
export RESULTS_DIR_TIMESTAMP=$(date +%Y-%m-%d_%H_%M_%S)
|
||||||
|
export RESULTS_DIR="/root/Results/controller_${RESULTS_DIR_TIMESTAMP}"
|
||||||
|
mkdir -p "$RESULTS_DIR"
|
||||||
|
|
||||||
|
export TS_FORMAT="${TS_FORMAT:-'[%Y-%m-%d %H:%M:%.S]'}"
|
||||||
|
export LOG_PREFIX="$(date +%Y-%m-%d_%H_%M_%S)"
|
||||||
|
|
||||||
|
export TX_FREQ=3.32e9
|
||||||
|
export RX_FREQ=3.32e9
|
||||||
|
|
||||||
|
export PROFILE_DIR=$AERPAW_REPO"/AHN/E-VM/Profile_software"
|
||||||
|
cd $PROFILE_DIR"/ProfileScripts"
|
||||||
|
|
||||||
|
screen -S controller -dm \
|
||||||
|
bash -c "stdbuf -oL -eL ./Vehicle/startVehicle.sh \
|
||||||
|
| ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_controller_log.txt"
|
||||||
|
|
||||||
|
schedule_stop.sh 30
|
||||||
174
plots_1_2.m
Normal file
174
plots_1_2.m
Normal file
@@ -0,0 +1,174 @@
|
|||||||
|
clear;
|
||||||
|
|
||||||
|
%% Load data
|
||||||
|
dataPath = fullfile('.', 'sandbox', 'plot1');
|
||||||
|
dataFiles = dir(dataPath);
|
||||||
|
dataFiles = dataFiles(~startsWith({dataFiles.name}, '.'));
|
||||||
|
simInits = dataFiles(endsWith({dataFiles.name}, 'miSimInits.mat'));
|
||||||
|
simHists = dataFiles(endsWith({dataFiles.name}, 'miSimHist.mat'));
|
||||||
|
assert(length(simHists) == length(simInits), "input data availability mismatch");
|
||||||
|
|
||||||
|
%% Aggregate run data
|
||||||
|
nRuns = length(simHists);
|
||||||
|
Cfinal = NaN(nRuns, 1);
|
||||||
|
nAgents = NaN(nRuns, 1);
|
||||||
|
doubleIntegrator = NaN(nRuns, 1);
|
||||||
|
numObjective = NaN(nRuns, 1);
|
||||||
|
commsRadius = NaN(nRuns, 1);
|
||||||
|
collisionRadius = NaN(nRuns, 1);
|
||||||
|
maxAgents = 6;
|
||||||
|
alphaDist = NaN(maxAgents, nRuns);
|
||||||
|
positions = cell(maxAgents, nRuns);
|
||||||
|
adjacency = cell(nRuns, 1);
|
||||||
|
|
||||||
|
for ii = 1:nRuns
|
||||||
|
initName = strrep(simInits(ii).name, "_miSimInits.mat", "");
|
||||||
|
histName = strrep(simHists(ii).name, "_miSimHist.mat", "");
|
||||||
|
assert(initName == histName);
|
||||||
|
|
||||||
|
init = load(fullfile(simInits(ii).folder, simInits(ii).name));
|
||||||
|
hist = load(fullfile(simHists(ii).folder, simHists(ii).name));
|
||||||
|
|
||||||
|
Cfinal(ii) = hist.out.perf(end) / init.objectiveIntegral;
|
||||||
|
nAgents(ii) = init.numAgents;
|
||||||
|
doubleIntegrator(ii) = init.useDoubleIntegrator;
|
||||||
|
numObjective(ii) = size(init.objectivePos, 1);
|
||||||
|
commsRadius(ii) = unique(init.comRange);
|
||||||
|
collisionRadius(ii) = unique(init.collisionRadius);
|
||||||
|
|
||||||
|
adjacency{ii} = hist.out.constraintAdjacency(:, :, 1);
|
||||||
|
for jj = 1:nAgents(ii)
|
||||||
|
alphaDist(jj, ii) = hist.out.agent(jj).sensor.alphaDist;
|
||||||
|
positions{jj, ii} = hist.out.agent(jj).pos;
|
||||||
|
assert(hist.out.agent(jj).commsRadius == commsRadius(ii));
|
||||||
|
assert(hist.out.agent(jj).collisionRadius == collisionRadius(ii));
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
commsRadius = unique(commsRadius); assert(isscalar(commsRadius));
|
||||||
|
collisionRadius = unique(collisionRadius); assert(isscalar(collisionRadius));
|
||||||
|
sensorTypes = flip(unique(alphaDist(1, :)));
|
||||||
|
nValues = sort(unique(nAgents));
|
||||||
|
nGroups = length(nValues);
|
||||||
|
|
||||||
|
%% Build config labels
|
||||||
|
baseConfig = strings(nRuns, 1);
|
||||||
|
for ii = 1:nRuns
|
||||||
|
s = "";
|
||||||
|
if numObjective(ii) == 1
|
||||||
|
s = s + "A";
|
||||||
|
elseif numObjective(ii) == 2
|
||||||
|
s = s + "B";
|
||||||
|
end
|
||||||
|
if alphaDist(1, ii) == sensorTypes(1)
|
||||||
|
s = s + "_I";
|
||||||
|
elseif alphaDist(1, ii) == sensorTypes(2)
|
||||||
|
s = s + "_II";
|
||||||
|
end
|
||||||
|
if ~doubleIntegrator(ii)
|
||||||
|
s = s + "_alpha";
|
||||||
|
else
|
||||||
|
s = s + "_beta";
|
||||||
|
end
|
||||||
|
baseConfig(ii) = s;
|
||||||
|
end
|
||||||
|
configOrder = unique(baseConfig(nAgents == nValues(1)), 'stable');
|
||||||
|
nConfigs = length(configOrder);
|
||||||
|
configLabels = ["$AI\alpha$"; "$AI\beta$"; "$AII\alpha$"; "$BI\beta$"];
|
||||||
|
|
||||||
|
%% Plot 1: Final normalized coverage
|
||||||
|
close all;
|
||||||
|
f1 = figure;
|
||||||
|
x1 = axes;
|
||||||
|
|
||||||
|
C_mean = NaN(nGroups, nConfigs);
|
||||||
|
C_var = NaN(nGroups, nConfigs);
|
||||||
|
for ii = 1:nGroups
|
||||||
|
for jj = 1:nConfigs
|
||||||
|
mask = (nAgents == nValues(ii)) & (baseConfig == configOrder(jj));
|
||||||
|
C_mean(ii, jj) = mean(Cfinal(mask));
|
||||||
|
C_var(ii, jj) = var(Cfinal(mask));
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
bar(x1, C_mean);
|
||||||
|
set(x1, 'XTickLabel', string(nValues));
|
||||||
|
xlabel(x1, "Number of agents");
|
||||||
|
ylabel(x1, "Final coverage (normalized)");
|
||||||
|
title(x1, "Final performance of parameterizations");
|
||||||
|
legend(x1, configLabels, "Interpreter", "latex", "Location", "northwest");
|
||||||
|
grid(x1, "on");
|
||||||
|
ylim(x1, [0, 1/2]);
|
||||||
|
|
||||||
|
savefig(f1, "plot1.fig");
|
||||||
|
exportgraphics(f1, "plot1.png");
|
||||||
|
|
||||||
|
%% Plot 2: Pairwise agent distances
|
||||||
|
f2 = figure;
|
||||||
|
x2 = axes;
|
||||||
|
|
||||||
|
% Compute pairwise distances only for connected agents (static topology)
|
||||||
|
maxPairs = nchoosek(maxAgents, 2);
|
||||||
|
pairDist = cell(maxPairs, nRuns);
|
||||||
|
for ii = 1:nRuns
|
||||||
|
A = adjacency{ii};
|
||||||
|
pp = 0;
|
||||||
|
for jj = 1:nAgents(ii)-1
|
||||||
|
for kk = jj+1:nAgents(ii)
|
||||||
|
pp = pp + 1;
|
||||||
|
if A(jj, kk)
|
||||||
|
pairDist{pp, ii} = vecnorm(positions{jj, ii} - positions{kk, ii}, 2, 2);
|
||||||
|
end
|
||||||
|
end
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
% Per-run statistics across all pairs and timesteps
|
||||||
|
meanPairDist = NaN(nRuns, 1);
|
||||||
|
minPairDist = NaN(nRuns, 1);
|
||||||
|
maxPairDist = NaN(nRuns, 1);
|
||||||
|
for ii = 1:nRuns
|
||||||
|
nPairs = nchoosek(nAgents(ii), 2);
|
||||||
|
D = vertcat(pairDist{1:nPairs, ii});
|
||||||
|
meanPairDist(ii) = mean(D, "omitmissing");
|
||||||
|
minPairDist(ii) = min(D);
|
||||||
|
maxPairDist(ii) = max(D);
|
||||||
|
end
|
||||||
|
|
||||||
|
% Aggregate across trials per (n, config) group
|
||||||
|
meanD = NaN(nGroups, nConfigs);
|
||||||
|
minD = NaN(nGroups, nConfigs);
|
||||||
|
maxD = NaN(nGroups, nConfigs);
|
||||||
|
for ii = 1:nGroups
|
||||||
|
for jj = 1:nConfigs
|
||||||
|
mask = (nAgents == nValues(ii)) & (baseConfig == configOrder(jj));
|
||||||
|
meanD(ii, jj) = mean(meanPairDist(mask));
|
||||||
|
minD(ii, jj) = min(minPairDist(mask));
|
||||||
|
maxD(ii, jj) = max(maxPairDist(mask));
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
% Plot whiskers (min to max) with mean markers
|
||||||
|
barWidth = 0.8;
|
||||||
|
groupWidth = barWidth / nConfigs;
|
||||||
|
hold(x2, 'on');
|
||||||
|
for jj = 1:nConfigs
|
||||||
|
xPos = (1:nGroups) + (jj - (nConfigs + 1) / 2) * groupWidth;
|
||||||
|
errorbar(x2, xPos, meanD(:, jj), meanD(:, jj) - minD(:, jj), maxD(:, jj) - meanD(:, jj), ...
|
||||||
|
'o', 'LineWidth', 1.5, 'MarkerSize', 6, 'CapSize', 10);
|
||||||
|
end
|
||||||
|
hold(x2, 'off');
|
||||||
|
set(x2, 'XTick', 1:nGroups, 'XTickLabel', string(nValues));
|
||||||
|
xlabel(x2, "Number of agents");
|
||||||
|
ylabel(x2, "Pairwise distance");
|
||||||
|
title(x2, "Pairwise Agent Distances (min/mean/max)");
|
||||||
|
legend(x2, configLabels, "Interpreter", "latex");
|
||||||
|
grid(x2, "on");
|
||||||
|
yline(x2, collisionRadius, 'r--', "Label", "Collision Radius", ...
|
||||||
|
"LabelHorizontalAlignment", "left", "HandleVisibility", "off");
|
||||||
|
yline(x2, commsRadius, 'r--', "Label", "Communications Radius", ...
|
||||||
|
"LabelHorizontalAlignment", "left", "HandleVisibility", "off");
|
||||||
|
ylim(x2, [0, commsRadius + 5]);
|
||||||
|
|
||||||
|
savefig(f2, "plot2.fig");
|
||||||
|
exportgraphics(f2, "plot2.png");
|
||||||
120
plots_3_4.m
Normal file
120
plots_3_4.m
Normal file
@@ -0,0 +1,120 @@
|
|||||||
|
clear;
|
||||||
|
|
||||||
|
%% Load data
|
||||||
|
dataPath = fullfile('.', 'sandbox', 'plot3');
|
||||||
|
dataFiles = dir(dataPath);
|
||||||
|
dataFiles = dataFiles(~startsWith({dataFiles.name}, '.'));
|
||||||
|
simInits = dataFiles(endsWith({dataFiles.name}, 'miSimInits.mat'));
|
||||||
|
simHists = dataFiles(endsWith({dataFiles.name}, 'miSimHist.mat'));
|
||||||
|
assert(length(simHists) == length(simInits), "input data availability mismatch");
|
||||||
|
assert(isscalar(simHists));
|
||||||
|
|
||||||
|
init = load(fullfile(simInits(1).folder, simInits(1).name));
|
||||||
|
hist = load(fullfile(simHists(1).folder, simHists(1).name));
|
||||||
|
hist = hist.out;
|
||||||
|
|
||||||
|
%% Plot 3: Per-agent and cumulative normalized performance
|
||||||
|
assert(size(init.objectivePos, 1) == 1);
|
||||||
|
assert(hist.useDoubleIntegrator);
|
||||||
|
|
||||||
|
nAgents = length(hist.agent);
|
||||||
|
agentLabels = "Agent " + string(1:nAgents)';
|
||||||
|
|
||||||
|
f3 = figure;
|
||||||
|
x3 = axes;
|
||||||
|
hold(x3, 'on');
|
||||||
|
plot(x3, hist.perf ./ init.objectiveIntegral, "LineWidth", 2);
|
||||||
|
for ii = 1:nAgents
|
||||||
|
plot(x3, hist.agent(ii).perf ./ init.objectiveIntegral, "LineWidth", 2);
|
||||||
|
end
|
||||||
|
hold(x3, 'off');
|
||||||
|
grid(x3, "on");
|
||||||
|
ylabel(x3, "Performance (normalized)");
|
||||||
|
xlabel(x3, "Timestep");
|
||||||
|
legend(x3, ["Cumulative"; agentLabels], "Location", "northwest");
|
||||||
|
title(x3, "$AII\beta$ Performance", "Interpreter", "latex");
|
||||||
|
|
||||||
|
savefig(f3, "plot3.fig");
|
||||||
|
exportgraphics(f3, "plot3.png");
|
||||||
|
|
||||||
|
%% Plot 4: Pairwise distances and barrier functions
|
||||||
|
commsRadius = hist.agent(1).commsRadius;
|
||||||
|
collisionRadius = hist.agent(1).collisionRadius;
|
||||||
|
nPairs = nchoosek(nAgents, 2);
|
||||||
|
T = size(hist.agent(1).pos, 1);
|
||||||
|
|
||||||
|
% Compute pairwise distances over time
|
||||||
|
pairDistMat = NaN(T, nPairs);
|
||||||
|
pairLabels = strings(nPairs, 1);
|
||||||
|
pp = 0;
|
||||||
|
for jj = 1:nAgents-1
|
||||||
|
for kk = jj+1:nAgents
|
||||||
|
pp = pp + 1;
|
||||||
|
pairDistMat(:, pp) = vecnorm(hist.agent(jj).pos - hist.agent(kk).pos, 2, 2);
|
||||||
|
pairLabels(pp) = sprintf("Agents %d-%d Distance", jj, kk);
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
f4 = figure;
|
||||||
|
x4 = axes;
|
||||||
|
|
||||||
|
% Left Y-axis: pairwise distances
|
||||||
|
hold(x4, 'on');
|
||||||
|
hLeft = gobjects(nPairs, 1);
|
||||||
|
for pp = 1:nPairs
|
||||||
|
hLeft(pp) = plot(x4, pairDistMat(:, pp), 'LineWidth', 2);
|
||||||
|
end
|
||||||
|
yline(x4, collisionRadius, 'r--', "Label", "Collision Radius", ...
|
||||||
|
"LabelHorizontalAlignment", "left", "HandleVisibility", "off");
|
||||||
|
yline(x4, commsRadius, 'r--', "Label", "Communications Radius", ...
|
||||||
|
"LabelHorizontalAlignment", "left", "HandleVisibility", "off");
|
||||||
|
hold(x4, 'off');
|
||||||
|
xlabel(x4, "Timestep");
|
||||||
|
ylabel(x4, "Pairwise distance");
|
||||||
|
title(x4, "$AII\beta$ Pairwise Agent Distances and Barrier Function Values", "Interpreter", "latex");
|
||||||
|
grid(x4, "on");
|
||||||
|
|
||||||
|
savefig(f4, "plot4_distanceOnly.fig");
|
||||||
|
exportgraphics(f4, "plot4_distanceOnly.png");
|
||||||
|
|
||||||
|
% Right Y-axis: barrier function values
|
||||||
|
nObs = init.numObstacles;
|
||||||
|
nAA = nchoosek(nAgents, 2);
|
||||||
|
nAO = nAgents * nObs;
|
||||||
|
nAD = nAgents * 6;
|
||||||
|
nComms = size(hist.barriers, 1) - nAA - nAO - nAD;
|
||||||
|
|
||||||
|
colStart = 1;
|
||||||
|
comStart = colStart + nAA + nAO + nAD;
|
||||||
|
|
||||||
|
pairColors = lines(nAA);
|
||||||
|
|
||||||
|
yyaxis(x4, 'right');
|
||||||
|
hold(x4, 'on');
|
||||||
|
hRight = gobjects(nAA + nComms, 1);
|
||||||
|
rightLabels = strings(nAA + nComms, 1);
|
||||||
|
idx = 0;
|
||||||
|
for pp = 1:nAA
|
||||||
|
idx = idx + 1;
|
||||||
|
hRight(idx) = plot(x4, hist.barriers(colStart + pp - 1, :), '--', ...
|
||||||
|
'LineWidth', 1.5, 'Color', pairColors(pp, :));
|
||||||
|
rightLabels(idx) = sprintf('h_{col} %d', pp);
|
||||||
|
end
|
||||||
|
for pp = 1:nComms
|
||||||
|
idx = idx + 1;
|
||||||
|
hRight(idx) = plot(x4, hist.barriers(comStart + pp - 1, :), '-.', ...
|
||||||
|
'LineWidth', 1.5, 'Color', pairColors(pp, :));
|
||||||
|
rightLabels(idx) = sprintf('h_{com} %d', pp);
|
||||||
|
end
|
||||||
|
hold(x4, 'off');
|
||||||
|
ylabel(x4, "Barrier function $h$", "Interpreter", "latex");
|
||||||
|
|
||||||
|
% Y-axis limits
|
||||||
|
yyaxis(x4, 'left'); ylim(x4, [0, 25]);
|
||||||
|
yyaxis(x4, 'right'); ylim(x4, [0, 275]);
|
||||||
|
x4.YAxis(2).Color = 'k';
|
||||||
|
|
||||||
|
legend([hLeft(:); hRight(:)], [pairLabels(:); rightLabels(:)], "Location", "eastoutside");
|
||||||
|
|
||||||
|
savefig(f4, "plot4.fig");
|
||||||
|
exportgraphics(f4, "plot4.png");
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="1" type="DIR_SIGNIFIER"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="1" type="DIR_SIGNIFIER"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info Ref="aerpaw/scripts" Type="Relative"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="6402cbb5-c767-4c8b-bd7c-b2d7cf1055fc" type="Reference"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info Ref="aerpaw/radio" Type="Relative"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="df3a85ba-fb12-4318-81b9-0233555f7fe7" type="Reference"/>
|
||||||
@@ -0,0 +1,6 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info>
|
||||||
|
<Category UUID="FileClassCategory">
|
||||||
|
<Label UUID="test"/>
|
||||||
|
</Category>
|
||||||
|
</Info>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="results.m" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="radio" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="scripts" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="1" type="DIR_SIGNIFIER"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="1" type="DIR_SIGNIFIER"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="1" type="DIR_SIGNIFIER"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="plotGpsLogs.m" type="File"/>
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="plotGpsCsvs.m" type="File"/>
|
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="readRadioLogs.m" type="File"/>
|
||||||
@@ -0,0 +1,6 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info>
|
||||||
|
<Category UUID="FileClassCategory">
|
||||||
|
<Label UUID="design"/>
|
||||||
|
</Category>
|
||||||
|
</Info>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="readGpsLogs.m" type="File"/>
|
||||||
@@ -0,0 +1,6 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info>
|
||||||
|
<Category UUID="FileClassCategory">
|
||||||
|
<Label UUID="design"/>
|
||||||
|
</Category>
|
||||||
|
</Info>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="plotRadioLogs.m" type="File"/>
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="readGpsCsv.m" type="File"/>
|
|
||||||
@@ -0,0 +1,6 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info>
|
||||||
|
<Category UUID="FileClassCategory">
|
||||||
|
<Label UUID="design"/>
|
||||||
|
</Category>
|
||||||
|
</Info>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="resultsAnalysis.m" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="1" type="DIR_SIGNIFIER"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startchannelsounderTXGRC.sh" type="File"/>
|
||||||
@@ -0,0 +1,6 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info>
|
||||||
|
<Category UUID="FileClassCategory">
|
||||||
|
<Label UUID="design"/>
|
||||||
|
</Category>
|
||||||
|
</Info>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startchannelsounderRXGRC.sh" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="CSwSNRTX.py" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="CSwSNRRX.py" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="updateScripts.sh" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="1" type="DIR_SIGNIFIER"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startexperiment_controller.sh" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startRadio.sh" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="1" type="DIR_SIGNIFIER"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startexperiment.sh" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startVehicle.sh" type="File"/>
|
||||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user