47 Commits

Author SHA1 Message Date
kdee bdc31ccad5 plot script fixes 2026-03-04 23:06:06 -08:00
kdee d5c7f4f11f finalized plotting utility 2026-03-04 22:32:39 -08:00
kdee 110ff87c57 type error fix 2026-03-04 21:27:51 -08:00
kdee 51e7533369 added radio plotting tools 2026-03-04 21:22:33 -08:00
kdee 3fd4462f11 plotting update 2026-03-04 18:42:17 -08:00
kdee 12b6e79f1e fixed GPS log out path 2026-03-04 18:21:39 -08:00
kdee e801018d9c radio experiment TDM working 2026-03-04 17:26:50 -08:00
kdee d5307f63e9 seems to line up well again, constrainMotion updates 2026-03-03 20:14:55 -08:00
kdee ac52e0414d scenario update, quadprog issue 2026-03-03 19:32:13 -08:00
kdee f140b55a63 obstacle respected now 2026-03-03 18:53:19 -08:00
kdee 6b5d33962b obstacles in but ignored 2026-03-03 16:42:15 -08:00
kdee 8ebeda3bf0 scenario - obstacle - one around, one over 2026-03-03 16:22:13 -08:00
kdee fe7b1b2ed3 per-UAV parameters 2026-03-03 16:18:07 -08:00
kdee 252423eb29 moved reader out of miSim, went to event-based guidance 2026-03-03 15:53:22 -08:00
kdee 351a9bd16f removed prompt to continue 2026-03-03 15:22:10 -08:00
kdee 2b853466f2 results compare favorably 2026-03-02 19:06:45 -08:00
kdee d49bf61d1d scenario edits 2026-03-02 18:18:40 -08:00
kdee 032f50774f improved globe plotting 2026-03-02 16:15:03 -08:00
kdee e40d2e4614 moved origin to get more space from geofence 2026-03-02 12:15:01 -08:00
kdee 387d6aea56 scenario csv on both platforms 2026-02-28 19:36:58 -08:00
kdee 0bf293c95e added slack in collision avoidance constraint 2026-02-27 16:06:10 -08:00
kdee db6df5f263 csv parse update 2026-02-25 11:44:59 -08:00
kdee d89fa38ba1 testing fixes 2026-02-25 11:02:56 -08:00
kdee c2fa2b524a added constraint violation recovery mechanism 2026-02-24 19:30:14 -08:00
kdee bb97502be5 codegen fixes, bug fixes, gets running on testbed environment 2026-02-24 19:05:54 -08:00
kdee fb9feac23d gps log plotting 2026-02-16 11:19:10 -08:00
kdee fd6ebf538c aerpaw gps csv reader 2026-02-15 21:50:13 -08:00
kdee a328eae126 gps logging updates 2026-02-15 17:29:14 -08:00
kdee c060dfad06 respect geofence, move from socket to async/await 2026-02-13 18:55:07 -08:00
kdee 05bf99f061 more config cleanup 2026-02-13 18:16:27 -08:00
kdee 77ac58a8a2 config cleanup 2026-02-13 18:06:06 -08:00
kdee 525d213e6a project cleanup 2026-02-07 14:36:53 -08:00
kdee f434e1a685 logging consistency 2026-02-02 12:16:13 -08:00
kdee 330c1e5d54 message type updates 2026-02-01 16:02:18 -08:00
kdee f6e1f13bb5 removed potentially faulty environment detection in favor of explicit setting 2026-02-01 11:34:35 -08:00
kdee 79b03345ba refactor experiment config 2026-02-01 11:08:04 -08:00
kdee a965dff4ca added parallel message receiving for previously implemented messaging where necessary 2026-01-30 18:28:19 -08:00
kdee 448db1e0e3 added RTL and LAND capabilities 2026-01-30 18:16:33 -08:00
kdee dd82cb3956 kinda working 2026-01-30 15:56:00 -08:00
kdee 6b8e26eb69 added real autopilot connection info 2026-01-29 22:07:53 -08:00
kdee 654de7c2a1 allowed connection to real autopilot 2026-01-29 21:11:45 -08:00
kdee 338bb6c340 added aerpawlib capabilities to uav script 2026-01-29 20:56:54 -08:00
kdee 6604928f8f reorganized and added aerpawlib submodule 2026-01-29 20:08:51 -08:00
kdee aed1924297 sending starting positions to agents (not verified on AERPAW yet) 2026-01-29 16:42:19 -08:00
kdee fe106f31cd cleanup demo 2026-01-28 23:20:11 -08:00
kdee 8c5c315380 basic implementation of client/server for AERPAW, whole lot of mess included 2026-01-28 22:29:17 -08:00
kdee b444e44d33 experiment setup 2026-01-28 15:47:09 -08:00
95 changed files with 368 additions and 1224 deletions
-1
View File
@@ -48,7 +48,6 @@ sandbox/*
# Figures # Figures
*.fig *.fig
*.png
# Python Virtual Environment # Python Virtual Environment
aerpaw/venv/ aerpaw/venv/
+3
View File
@@ -0,0 +1,3 @@
[submodule "aerpaw/aerpawlib"]
path = aerpaw/aerpawlib
url = https://github.com/morzack/aerpawlib-vehicle-control.git
-2
View File
@@ -6,8 +6,6 @@ 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;
+1 -4
View File
@@ -15,9 +15,6 @@ 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;
@@ -36,4 +33,4 @@ function obj = initialize(obj, pos, collisionGeometry, sensorModel, comRange, ma
% Initialize FOV cone % Initialize FOV cone
obj.fovGeometry = cone; obj.fovGeometry = cone;
obj.fovGeometry = obj.fovGeometry.initialize([obj.pos(1:3)], tand(obj.sensorModel.alphaTilt) * obj.pos(3), obj.pos(3), REGION_TYPE.FOV, sprintf("%s FOV", obj.label)); obj.fovGeometry = obj.fovGeometry.initialize([obj.pos(1:3)], tand(obj.sensorModel.alphaTilt) * obj.pos(3), obj.pos(3), REGION_TYPE.FOV, sprintf("%s FOV", obj.label));
end end
+12 -27
View File
@@ -1,4 +1,4 @@
function obj = run(obj, domain, partitioning, timestepIndex, index, agents, useDoubleIntegrator, dampingCoeff, dt) function obj = run(obj, domain, partitioning, timestepIndex, index, agents)
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,21 +6,11 @@ function obj = run(obj, domain, partitioning, timestepIndex, index, agents, useD
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(:))
@@ -85,25 +75,20 @@ function obj = run(obj, domain, partitioning, timestepIndex, index, agents, useD
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 state % Compute unconstrained next position.
if useDoubleIntegrator % Guard against near-zero gradient: when sensor performance is saturated
% Double-integrator: gradient produces desired acceleration with damping % or near-zero across the whole partition, rateFactor -> Inf and pNext
if gradNorm < 1e-100 % explodes. Stay put instead.
a_gradient = zeros(1, 3); if gradNorm < 1e-100
else pNext = obj.pos;
% 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
% Single-integrator: gradient directly sets position step pNext = obj.pos + (targetRate / gradNorm) * gradC;
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")
+48 -88
View File
@@ -8,41 +8,41 @@ function [obj] = constrainMotion(obj)
nAgents = size(obj.agents, 1); nAgents = size(obj.agents, 1);
% Compute current velocity and desired control input if nAgents < 2
v = zeros(nAgents, 3); % current velocity (for drift term in DI mode) nAAPairs = 0;
u_desired = zeros(nAgents, 3); % desired control: velocity (SI) or acceleration (DI) else
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
if obj.useDoubleIntegrator v(ii, :) = (obj.agents{ii}.pos - obj.agents{ii}.lastPos) ./ obj.timestep;
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 ~obj.useDoubleIntegrator && (all(isnan(v), "all") || all(v == zeros(nAgents, 3), "all")) if all(isnan(v), "all") || all(v == zeros(nAgents, 3), "all")
% Single-integrator: agents are not attempting to move % Agents are not attempting to move, so there is no motion to be
return; % constrained
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(obj.numBarriers, 3 * nAgents); A = zeros(total, 3 * nAgents);
b = zeros(obj.numBarriers, 1); b = zeros(total, 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}.lastPos - obj.agents{jj}.lastPos)^2 - (obj.agents{ii}.collisionGeometry.radius + obj.agents{jj}.collisionGeometry.radius)^2; 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(jj, ii) = h(ii, jj); h(jj, ii) = h(ii, jj);
A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.lastPos - obj.agents{jj}.lastPos); A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.pos - obj.agents{jj}.pos);
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
@@ -60,22 +60,16 @@ function [obj] = constrainMotion(obj)
end end
end end
idx = length(h(triu(true(size(h)), 1)));
if coder.target('MATLAB')
obj.barriers(1:idx, obj.timestepIndex) = h(triu(true(size(h)), 1));
end
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}.lastPos); cPos = obj.obstacles{jj}.closestToPoint(obj.agents{ii}.pos);
hObs(ii, jj) = dot(obj.agents{ii}.lastPos - cPos, obj.agents{ii}.lastPos - cPos) - obj.agents{ii}.collisionGeometry.radius^2; hObs(ii, jj) = dot(obj.agents{ii}.pos - cPos, obj.agents{ii}.pos - cPos) - obj.agents{ii}.collisionGeometry.radius^2;
A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.lastPos - cPos); A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.pos - 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;
@@ -86,56 +80,51 @@ function [obj] = constrainMotion(obj)
end end
end end
if coder.target('MATLAB')
obj.barriers(idx:(idx + numel(hObs) - 1), obj.timestepIndex) = reshape(hObs, [], 1);
end
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}.lastPos(1) - obj.domain.minCorner(1)) - obj.agents{ii}.collisionGeometry.radius; h_xMin = (obj.agents{ii}.pos(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}.lastPos(1)) - obj.agents{ii}.collisionGeometry.radius; h_xMax = (obj.domain.maxCorner(1) - obj.agents{ii}.pos(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}.lastPos(2) - obj.domain.minCorner(2)) - obj.agents{ii}.collisionGeometry.radius; h_yMin = (obj.agents{ii}.pos(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}.lastPos(2)) - obj.agents{ii}.collisionGeometry.radius; h_yMax = (obj.domain.maxCorner(2) - obj.agents{ii}.pos(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}.lastPos(3) - obj.minAlt) - obj.agents{ii}.collisionGeometry.radius; h_zMin = (obj.agents{ii}.pos(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}.lastPos(3)) - obj.agents{ii}.collisionGeometry.radius; h_zMax = (obj.domain.maxCorner(3) - obj.agents{ii}.pos(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;
end
if coder.target('MATLAB') if coder.target('MATLAB')
obj.barriers(idx:(idx + 5), obj.timestepIndex) = [h_xMin; h_xMax; h_yMin; h_yMax; h_zMin; h_zMax]; % Save off h function values (logging only not needed in compiled mode)
end obj.h(:, obj.timestepIndex) = [h(triu(true(nAgents), 1)); reshape(hObs, [], 1); h_xMin; h_xMax; h_yMin; h_yMax; h_zMin; h_zMax;];
idx = idx + 6;
end end
% Add communication network constraints % Add communication network constraints
@@ -144,44 +133,21 @@ 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)
paddingFactor = 0.9; % Barrier at 90% of actual range; real comms still work beyond this 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;
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}.lastPos - obj.agents{jj}.lastPos); A(kk, (3 * ii - 2):(3 * ii)) = 2 * (obj.agents{ii}.pos - obj.agents{jj}.pos);
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
if coder.target('MATLAB')
obj.barriers(idx:(idx + length(hComms(triu(true(size(hComms)), 1))) - 1), obj.timestepIndex) = hComms(triu(true(size(hComms)), 1));
end
% Double-integrator: transform QP from velocity to acceleration space. % Solve QP program generated earlier
% Single-integrator constraint: A * v <= b vhat = reshape(v', 3 * nAgents, 1);
% 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 * uhat; f = -2 * vhat;
% Update solution based on constraints % Update solution based on constraints
if coder.target('MATLAB') if coder.target('MATLAB')
@@ -191,8 +157,8 @@ 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);
[uNew, ~, exitflag] = quadprog(H, double(f), A, b, [], [], [], [], x0, opt); [vNew, ~, exitflag] = quadprog(H, double(f), A, b, [], [], [], [], x0, opt);
uNew = reshape(uNew, 3, nAgents)'; vNew = reshape(vNew, 3, nAgents)';
if exitflag < 0 if exitflag < 0
% Infeasible or other hard failure: hold all agents at current positions % Infeasible or other hard failure: hold all agents at current positions
@@ -201,9 +167,9 @@ function [obj] = constrainMotion(obj)
else else
fprintf("[constrainMotion] QP infeasible (exitflag=%d), holding positions\n", int16(exitflag)); fprintf("[constrainMotion] QP infeasible (exitflag=%d), holding positions\n", int16(exitflag));
end end
uNew = zeros(nAgents, 3); vNew = zeros(nAgents, 3);
elseif exitflag == 0 elseif exitflag == 0
% Max iterations exceeded: use suboptimal solution already in uNew % Max iterations exceeded: use suboptimal solution already in vNew
if coder.target('MATLAB') if coder.target('MATLAB')
warning("QP max iterations exceeded, using suboptimal solution."); warning("QP max iterations exceeded, using suboptimal solution.");
else else
@@ -211,16 +177,10 @@ function [obj] = constrainMotion(obj)
end end
end end
% Update agent state using the constrained control input % Update the "next position" that was previously set by unconstrained
for ii = 1:size(uNew, 1) % GA using the constrained solution produced here
if obj.useDoubleIntegrator for ii = 1:size(vNew, 1)
% uNew is constrained acceleration obj.agents{ii}.pos = obj.agents{ii}.lastPos + vNew(ii, :) * obj.timestep;
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
@@ -228,4 +188,4 @@ function [obj] = constrainMotion(obj)
% Running at the simulation level is just meant to simplify the % Running at the simulation level is just meant to simplify the
% simulation % simulation
end end
+5 -38
View File
@@ -1,4 +1,4 @@
function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, minAlt, timestep, maxIter, obstacles, makePlots, makeVideo, useDoubleIntegrator, dampingCoeff, useFixedTopology) function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, minAlt, timestep, maxIter, obstacles, makePlots, makeVideo)
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,9 +11,6 @@ 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")};
@@ -89,18 +86,9 @@ function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, m
obj.barrierExponent = barrierExponent; obj.barrierExponent = barrierExponent;
obj.minAlt = minAlt; obj.minAlt = minAlt;
% Set dynamics model % Compute adjacency matrix and lesser neighbors
obj.useDoubleIntegrator = useDoubleIntegrator;
obj.dampingCoeff = dampingCoeff;
obj.useFixedTopology = useFixedTopology;
% Compute adjacency matrix and network topology
obj = obj.updateAdjacency(); obj = obj.updateAdjacency();
if obj.useFixedTopology obj = obj.lesserNeighbor();
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)';
@@ -109,39 +97,18 @@ function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, m
% Prepare performance data store (at t = 0, all have 0 performance) % Prepare performance data store (at t = 0, all have 0 performance)
obj.perf = [zeros(size(obj.agents, 1) + 1, 1), NaN(size(obj.agents, 1) + 1, size(obj.partitioningTimes, 1) - 1)]; obj.perf = [zeros(size(obj.agents, 1) + 1, 1), NaN(size(obj.agents, 1) + 1, size(obj.partitioningTimes, 1) - 1)];
% Prepare h function data store
obj.h = NaN(size(obj.agents, 1) * (size(obj.agents, 1) - 1) / 2 + size(obj.agents, 1) * size(obj.obstacles, 1) + 6, size(obj.times, 1));
end end
% 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();
+1 -19
View File
@@ -79,23 +79,6 @@ 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");
@@ -141,7 +124,6 @@ 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
-87
View File
@@ -1,87 +0,0 @@
function obj = initializeFromInits(obj, initsPath)
% INITIALIZEFROMINITS Initialize miSim from a saved simInits matfile.
%
% Loads all simulation parameters and initial agent states written by
% writeInits(), reconstructs domain, objective, agents, and obstacles, then
% calls the standard obj.initialize() method. Plots and video are disabled.
%
% Usage:
% sim = sim.initializeFromInits('sandbox/2025_01_01_12_00_00_miSimInits.mat');
arguments (Input)
obj (1, 1) {mustBeA(obj, 'miSim')};
initsPath (1, 1) string;
end
arguments (Output)
obj (1, 1) {mustBeA(obj, 'miSim')};
end
inits = load(initsPath);
% ---- Build domain ------------------------------------------------------------
dom = rectangularPrism;
dom = dom.initialize([inits.domainMin; inits.domainMax], REGION_TYPE.DOMAIN, "Domain");
% ---- Build sensing objective -------------------------------------------------
dom.objective = sensingObjective;
% reshape guards against MATLAB flattening the 1×2×2 singleton dimension on load
objSigma = reshape(inits.objectiveSigma, [1 2 2]);
objFcn = objectiveFunctionWrapper(inits.objectivePos, objSigma);
dom.objective = dom.objective.initialize(objFcn, dom, ...
inits.discretizationStep, inits.protectedRange, inits.sensorPerformanceMinimum, ...
inits.objectivePos, objSigma);
% ---- Build agents ------------------------------------------------------------
numAgents = inits.numAgents;
agentList = cell(numAgents, 1);
for ii = 1:numAgents
pos = inits.pos(ii, :);
sensor = sigmoidSensor;
sensor = sensor.initialize(inits.alphaDist(ii), inits.betaDist(ii), ...
inits.alphaTilt(ii), inits.betaTilt(ii));
geom = spherical;
geom = geom.initialize(pos, inits.collisionRadius(ii), REGION_TYPE.COLLISION, ...
sprintf("UAV %d Collision", ii));
ag = agent;
ag = ag.initialize(pos, geom, sensor, inits.comRange(ii), inits.maxIter, ...
inits.initialStepSize(ii), sprintf("UAV %d", ii));
agentList{ii} = ag;
end
% ---- Build obstacles ---------------------------------------------------------
numObstacles = inits.numObstacles;
obstacleList = cell(numObstacles, 1);
if numObstacles > 0
for ii = 1:numObstacles
obs = rectangularPrism;
obs = obs.initialize([inits.obsMinCorners(ii, :); inits.obsMaxCorners(ii, :)], ...
REGION_TYPE.OBSTACLE, sprintf("Obstacle %d", ii));
obstacleList{ii} = obs;
end
end
% ---- Optional backward-compat fields -----------------------------------------
if isfield(inits, 'useDoubleIntegrator')
useDoubleIntegrator = logical(inits.useDoubleIntegrator);
else
useDoubleIntegrator = false;
end
if isfield(inits, 'dampingCoeff')
dampingCoeff = inits.dampingCoeff;
else
dampingCoeff = 2.0;
end
if isfield(inits, 'useFixedTopology')
useFixedTopology = logical(inits.useFixedTopology);
else
useFixedTopology = false;
end
% ---- Initialize simulation (plots and video disabled) ------------------------
obj = obj.initialize(dom, agentList, inits.barrierGain, inits.barrierExponent, ...
inits.minAlt, inits.timestep, inits.maxIter, obstacleList, ...
false, false, useDoubleIntegrator, dampingCoeff, useFixedTopology);
end
+3 -9
View File
@@ -7,6 +7,7 @@ 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
@@ -17,17 +18,11 @@ 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 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 % Indicies for various plot types in the main tiled layout figure
spatialPlotIndices = [6, 4, 3, 2]; 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)
@@ -45,7 +40,6 @@ classdef miSim
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
@@ -54,6 +48,7 @@ classdef miSim
partitionGraphIndex = 1; partitionGraphIndex = 1;
% CBF plotting % CBF plotting
h; % h function values
hf; % h function plotting figure hf; % h function plotting figure
caPlot; % objects for collision avoidance h function plot caPlot; % objects for collision avoidance h function plot
obsPlot; % objects for obstacle h function plot obsPlot; % objects for obstacle h function plot
@@ -66,13 +61,12 @@ 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
[obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, minAlt, timestep, maxIter, obstacles, makePlots, makeVideo); [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, minAlt, timestep, maxIter, obstacles, makePlots, makeVideo);
[obj] = initializeFromCsv(obj, csvPath); [obj] = initializeFromCsv(obj, csvPath);
[obj] = initializeFromInits(obj, initsPath);
[obj] = plotFromSimHist(obj, initsPath, histPath);
[obj] = run(obj); [obj] = run(obj);
[obj] = lesserNeighbor(obj); [obj] = lesserNeighbor(obj);
[obj] = constrainMotion(obj); [obj] = constrainMotion(obj);
-93
View File
@@ -1,93 +0,0 @@
function obj = plotFromSimHist(obj, initsPath, histPath)
% PLOTFROMSIMHIST Reconstruct all three miSim plots from saved matfiles.
%
% Loads the simInits matfile to rebuild domain/obstacle/objective/agent
% geometry, then loads the simHist matfile to restore the full time-history
% arrays. Produces the same three figures that a live run would generate:
% 1. Sensor performance vs. time (obj.fPerf)
% 2. Barrier function values vs. time (obj.hf)
% 3. 3-D spatial figure with domain, obstacles, objective, agent trails,
% and final-timestep communications topology (obj.f)
%
% Usage:
% sim = miSim;
% sim = sim.plotFromSimHist( ...
% 'sandbox/2025_01_01_12_00_00_miSimHist.mat', ...
% 'sandbox/2025_01_01_12_00_00_miSimInits.mat');
arguments (Input)
obj (1, 1) {mustBeA(obj, 'miSim')};
initsPath (1, 1) string;
histPath (1, 1) string;
end
arguments (Output)
obj (1, 1) {mustBeA(obj, 'miSim')};
end
% ---- Reconstruct geometry from inits (plots disabled) --------------------
obj = obj.initializeFromInits(initsPath);
nAgents = size(obj.agents, 1);
% ---- Load history data ---------------------------------------------------
data = load(histPath);
out = data.out;
nHistTimesteps = size(out.barriers, 2);
nPosTimesteps = size(out.agent(1).pos, 1);
% ---- Populate barrier history --------------------------------------------
% out.barriers may be narrower than the pre-allocated obj.barriers if the
% run was shorter than maxIter; fill what we have and leave the rest NaN.
obj.barriers(:, 1:nHistTimesteps) = out.barriers;
% ---- Populate position history and advance agents to final positions -----
for ii = 1:nAgents
agentPos = out.agent(ii).pos; % (nPosTimesteps × 3)
nPts = size(agentPos, 1);
obj.posHist(ii, 1:nPts, :) = reshape(agentPos, [1, nPts, 3]);
obj.agents{ii}.pos = agentPos(end, :); % show final position in spatial plot
end
% ---- Set final constraint topology ---------------------------------------
obj.constraintAdjacencyMatrix = out.constraintAdjacency(:, :, end);
% ---- Recompute partitioning at final agent positions ---------------------
obj.partitioning = obj.agents{1}.partition(obj.agents, obj.domain.objective);
% ---- Enable plotting and produce spatial + barrier figures ---------------
obj.makePlots = true;
obj = obj.plot();
% ---- Performance figure (built directly live machinery is incremental) -
nPerfTimesteps = numel(out.perf);
times = (0:nPerfTimesteps - 1) * obj.timestep;
normFactor = 1 / max(out.perf);
obj.fPerf = figure;
ax = axes(obj.fPerf);
hold(ax, "on");
title(ax, "Sensor Performance");
xlabel(ax, "Time (s)");
ylabel(ax, "Sensor Performance");
grid(ax, "on");
legendStrings = strings(nAgents + 1, 1);
legendStrings(1) = "Total";
plot(ax, times, out.perf * normFactor, "LineWidth", 1.5);
for ii = 1:nAgents
agentPerf = out.agent(ii).perf;
agentTimes = times(1:numel(agentPerf));
plot(ax, agentTimes, agentPerf * normFactor);
if isfield(out.agent(ii), 'label')
legendStrings(ii + 1) = string(out.agent(ii).label);
else
legendStrings(ii + 1) = sprintf("Agent %d", ii);
end
end
legend(ax, legendStrings, "Location", "northwest");
hold(ax, "off");
% Bring spatial figure to the front
figure(obj.f);
end
+4 -13
View File
@@ -6,10 +6,6 @@ function obj = plotH(obj)
obj (1, 1) {mustBeA(obj, "miSim")}; obj (1, 1) {mustBeA(obj, "miSim")};
end end
nCA = size(obj.agents, 1) * (size(obj.agents, 1) - 1) / 2;
nObs = size(obj.agents, 1) * size(obj.obstacles, 1);
nDom = size(obj.agents, 1) * 6;
obj.hf = figure; obj.hf = figure;
tiledlayout(obj.hf, 4, 1, "TileSpacing", "tight", "Padding", "compact"); tiledlayout(obj.hf, 4, 1, "TileSpacing", "tight", "Padding", "compact");
@@ -19,7 +15,7 @@ function obj = plotH(obj)
xlabel(obj.hf.Children(1).Children(1), "Time (s)"); xlabel(obj.hf.Children(1).Children(1), "Time (s)");
title(obj.hf.Children(1).Children(1), "Collision Avoidance"); title(obj.hf.Children(1).Children(1), "Collision Avoidance");
hold(obj.hf.Children(1).Children(1), "on"); hold(obj.hf.Children(1).Children(1), "on");
obj.caPlot = plot(obj.barriers(1:nCA, :)'); obj.caPlot = plot(obj.h(1:(size(obj.agents, 1) * (size(obj.agents, 1) - 1) / 2), :)');
legendStrings = []; legendStrings = [];
for ii = 2:size(obj.agents, 1) for ii = 2:size(obj.agents, 1)
for jj = 1:(ii - 1) for jj = 1:(ii - 1)
@@ -35,7 +31,7 @@ function obj = plotH(obj)
xlabel(obj.hf.Children(1).Children(1), "Time (s)"); xlabel(obj.hf.Children(1).Children(1), "Time (s)");
title(obj.hf.Children(1).Children(1), "Obstacles"); title(obj.hf.Children(1).Children(1), "Obstacles");
hold(obj.hf.Children(1).Children(1), "on"); hold(obj.hf.Children(1).Children(1), "on");
obj.obsPlot = plot(obj.barriers((nCA + 1):(nCA + nObs), :)'); obj.obsPlot = plot(obj.h((1 + (size(obj.agents, 1) * (size(obj.agents, 1) - 1) / 2)):(((size(obj.agents, 1) * (size(obj.agents, 1) - 1) / 2)) + size(obj.agents, 1) * size(obj.obstacles, 1)), :)');
legendStrings = []; legendStrings = [];
for ii = 1:size(obj.obstacles, 1) for ii = 1:size(obj.obstacles, 1)
for jj = 1:size(obj.agents, 1) for jj = 1:size(obj.agents, 1)
@@ -51,13 +47,8 @@ function obj = plotH(obj)
xlabel(obj.hf.Children(1).Children(1), "Time (s)"); xlabel(obj.hf.Children(1).Children(1), "Time (s)");
title(obj.hf.Children(1).Children(1), "Domain"); title(obj.hf.Children(1).Children(1), "Domain");
hold(obj.hf.Children(1).Children(1), "on"); hold(obj.hf.Children(1).Children(1), "on");
obj.domPlot = plot(obj.barriers((nCA + nObs + 1):(nCA + nObs + nDom), :)'); obj.domPlot = plot(obj.h((1 + (((size(obj.agents, 1) * (size(obj.agents, 1) - 1) / 2)) + size(obj.agents, 1) * size(obj.obstacles, 1))):size(obj.h, 1), 1:end)');
domLabels = ["X Min", "X Max", "Y Min", "Y Max", "Z Min", "Z Max"]; legend(obj.hf.Children(1).Children(1), ["X Min"; "X Max"; "Y Min"; "Y Max"; "Z Min"; "Z Max";], "Location", "bestoutside");
legendStrings = strings(nDom, 1);
for ii = 1:size(obj.agents, 1)
legendStrings((ii - 1) * 6 + (1:6)) = sprintf("A%d ", ii) + domLabels;
end
legend(obj.hf.Children(1).Children(1), legendStrings, "Location", "bestoutside");
hold(obj.hf.Children(1).Children(2), "off"); hold(obj.hf.Children(1).Children(2), "off");
nexttile(obj.hf.Children(1)); nexttile(obj.hf.Children(1));
+3 -13
View File
@@ -30,19 +30,12 @@ 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
if ~obj.useFixedTopology obj = obj.lesserNeighbor();
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.useDoubleIntegrator, obj.dampingCoeff, obj.timestep); obj.agents{jj} = obj.agents{jj}.run(obj.domain, obj.partitioning, obj.timestepIndex, jj, obj.agents);
end end
% Adjust motion determined by unconstrained gradient ascent using % Adjust motion determined by unconstrained gradient ascent using
@@ -50,9 +43,8 @@ function [obj] = run(obj)
obj = constrainMotion(obj); obj = constrainMotion(obj);
if coder.target('MATLAB') if coder.target('MATLAB')
% Update agent position and velocity history arrays % Update agent position history array
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))];
@@ -71,12 +63,10 @@ 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
+5 -32
View File
@@ -6,52 +6,25 @@ 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
+5 -7
View File
@@ -61,15 +61,13 @@ function [obj] = updatePlots(obj)
end end
% Update h function plots % Update h function plots
nCA = size(obj.caPlot, 1); for ii = 1:size(obj.caPlot, 1)
nObs = size(obj.obsPlot, 1); obj.caPlot(ii).YData(obj.timestepIndex) = obj.h(ii, obj.timestepIndex);
for ii = 1:nCA
obj.caPlot(ii).YData(obj.timestepIndex) = obj.barriers(ii, obj.timestepIndex);
end end
for ii = 1:nObs for ii = 1:size(obj.obsPlot, 1)
obj.obsPlot(ii).YData(obj.timestepIndex) = obj.barriers(nCA + ii, obj.timestepIndex); obj.obsPlot(ii).YData(obj.timestepIndex) = obj.h(ii + size(obj.caPlot, 1), obj.timestepIndex);
end end
for ii = 1:size(obj.domPlot, 1) for ii = 1:size(obj.domPlot, 1)
obj.domPlot(ii).YData(obj.timestepIndex) = obj.barriers(nCA + nObs + ii, obj.timestepIndex); obj.domPlot(ii).YData(obj.timestepIndex) = obj.h(ii + size(obj.caPlot, 1) + size(obj.obsPlot, 1), obj.timestepIndex);
end end
end end
+5 -4
View File
@@ -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
error("Network is not connected"); warning("Network is not connected");
end end
if any(obj.adjacency - obj.constraintAdjacencyMatrix < 0, "all") if any(obj.adjacency - obj.constraintAdjacencyMatrix < 0, "all")
error("Eliminated network connections that were necessary"); warning("Eliminated network connections that were necessary");
end end
%% Obstacle Validators %% Obstacle Validators
@@ -20,9 +20,10 @@ 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 - 1e-3 if dot(d, d) < obj.agents{kk}.collisionGeometry.radius^2
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 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
end end
end end
end end
end end
+8 -19
View File
@@ -5,40 +5,29 @@ function writeInits(obj)
arguments (Output) arguments (Output)
end end
% User-supplied obstacles only: initialize() appends a floor obstacle at
% the end when minAlt > 0, so exclude it here to avoid double-counting on
% reconstruction (initializeFromInits re-adds the floor via minAlt).
numInputObs = size(obj.obstacles, 1) - (obj.minAlt > 0);
userObstacles = obj.obstacles(1:numInputObs);
% Collect agent parameters % Collect agent parameters
collisionRadii = cellfun(@(x) x.collisionGeometry.radius, obj.agents); collisionRadii = cellfun(@(x) x.collisionGeometry.radius, obj.agents);
alphaDist = cellfun(@(x) x.sensorModel.alphaDist, obj.agents); alphaDist = cellfun(@(x) x.sensorModel.alphaDist, obj.agents);
betaDist = cellfun(@(x) x.sensorModel.betaDist, obj.agents); betaDist = cellfun(@(x) x.sensorModel.betaDist, obj.agents);
alphaTilt = cellfun(@(x) x.sensorModel.alphaTilt, obj.agents); alphaTilt = cellfun(@(x) x.sensorModel.alphaTilt, obj.agents);
betaTilt = cellfun(@(x) x.sensorModel.betaTilt, obj.agents); betaTilt = cellfun(@(x) x.sensorModel.alphaDist, obj.agents);
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, userObstacles, 'UniformOutput', false));
obsMaxCorners = cell2mat(cellfun(@(x) x.maxCorner, userObstacles, 'UniformOutput', false));
% Combine with simulation parameters % Combine with simulation parameters
inits = struct("timestep", obj.timestep, "maxIter", obj.maxIter + 1, "minAlt", obj.minAlt, ... inits = struct("timestep", obj.timestep, "maxIter", obj.maxIter, "minAlt", obj.obstacles{end}.maxCorner(3), ...
"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", numInputObs, ... "barrierGain", obj.barrierGain, "barrierExponent", obj.barrierExponent, "numObstacles", size(obj.obstacles, 1), ...
"numAgents", size(obj.agents, 1), "collisionRadius", collisionRadii, "comRange", comRanges, ... "numAgents", size(obj.agents, 1), "collisionRadius", collisionRadii, "comRange", comRanges, "alphaDist", alphaDist, ...
"useDoubleIntegrator", obj.useDoubleIntegrator, "dampingCoeff", obj.dampingCoeff, "useFixedTopology", obj.useFixedTopology, ... "betaDist", betaDist, "alphaTilt", alphaTilt, "betaTilt", betaTilt, ...
"alphaDist", alphaDist, "betaDist", betaDist, "alphaTilt", alphaTilt, "betaTilt", betaTilt, ...
... % ^^^ PARAMETERS ^^^ | vvv STATES vvv ... % ^^^ PARAMETERS ^^^ | vvv STATES vvv
"pos", pos, "objectivePos", obj.domain.objective.groundPos, "objectiveSigma", obj.domain.objective.objectiveSigma, ... "pos", pos);
"domainMin", obj.domain.minCorner, "domainMax", obj.domain.maxCorner, ...
"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");
initsFile = fullfile(matlab.project.rootProject().RootFolder, "sandbox", initsFile); initsFile = fullfile(matlab.project.rootProject().RootFolder, "sandbox", initsFile);
save(initsFile, "-struct", "inits"); save(initsFile, "-struct", "inits");
end end
+5 -12
View File
@@ -1,4 +1,4 @@
function obj = initialize(obj, objectiveFunction, domain, discretizationStep, protectedRange, sensorPerformanceMinimum, objectiveMu, objectiveSigma) function obj = initialize(obj, objectiveFunction, domain, discretizationStep, protectedRange, sensorPerformanceMinimum)
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,8 +6,6 @@ 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")};
@@ -38,14 +36,9 @@ function obj = initialize(obj, objectiveFunction, domain, discretizationStep, pr
obj.values = obj.values ./ max(obj.values, [], "all"); obj.values = obj.values ./ max(obj.values, [], "all");
% store ground position % store ground position
idx = obj.values == 1; idx = obj.values == 1;
if any(isnan(objectiveMu)) obj.groundPos = [obj.X(idx), obj.Y(idx)];
obj.groundPos = [obj.X(idx), obj.Y(idx)]; obj.groundPos = obj.groundPos(1, 1:2); % for safety, in case 2 points are maximal (somehow)
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, ones(size(obj.groundPos, 1), 1) .* domain.center(3)]) > protectedRange, "Domain is crowding the sensing objective"); assert(domain.distance([obj.groundPos, domain.center(3)]) > protectedRange, "Domain is crowding the sensing objective")
end end
+3 -3
View File
@@ -11,16 +11,16 @@ 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 * 1.01 while domain.distance(mu) < protectedRange
mu = domain.random(); mu = domain.random();
end end
% Set random distribution parameters % Set random distribution parameters
sig = reshape([2 + rand * 2, 1; 1, 2 + rand * 2], [1 2 2]); sig = [2 + rand * 2, 1; 1, 2 + rand * 2];
% Set up random bivariate normal distribution function % Set up random bivariate normal distribution function
objectiveFunction = objectiveFunctionWrapper(mu(1:2), sig); objectiveFunction = objectiveFunctionWrapper(mu(1:2), sig);
% Regular initialization % Regular initialization
obj = obj.initialize(objectiveFunction, domain, discretizationStep, protectedRange, 1e-6, mu(1:2), sig); obj = obj.initialize(objectiveFunction, domain, discretizationStep, protectedRange);
end end
+1 -2
View File
@@ -2,8 +2,7 @@ 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(1, 2); groundPos = [NaN, NaN];
objectiveSigma = NaN(1, 2, 2);
discretizationStep = NaN; discretizationStep = NaN;
X = []; X = [];
Y = []; Y = [];
+1
Submodule aerpaw/aerpawlib added at 705fc699ef
+1 -1
View File
@@ -164,7 +164,7 @@ class UAVRunner(BasicRunner):
# Retry connection up to 10 times (~30 seconds total) # Retry connection up to 10 times (~30 seconds total)
reader, writer = None, None reader, writer = None, None
for attempt in range(100): for attempt in range(10):
try: try:
reader, writer = await asyncio.wait_for( reader, writer = await asyncio.wait_for(
asyncio.open_connection(self.server_ip, self.server_port), asyncio.open_connection(self.server_ip, self.server_port),
+5 -5
View File
@@ -12,8 +12,8 @@ tdm:
# ENU coordinate system origin (AERPAW Lake Wheeler Road Field) # ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
origin: origin:
lat: 35.72595214250436 lat: 35.72550610629396
lon: -78.69917609299937 lon: -78.70019657805574
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:
@@ -28,11 +28,11 @@ environments:
port: 5000 port: 5000
testbed: testbed:
# AERPAW testbed: E-VM listens, MAVLink Filter connects to us (UDP) # AERPAW testbed: E-VM listens, MAVLink Filter connects TO us (UDP)
mavlink: mavlink:
ip: "192.168.32.26" ip: "192.168.32.26"
port: 14550 port: 14550
# Controller runs on host machine (192.168.X.1, generally) # Controller runs on host machine (192.168.122.1 from E-VM perspective)
controller: controller:
ip: "192.168.112.1" ip: "192.168.122.1"
port: 5000 port: 5000
+5 -5
View File
@@ -12,8 +12,8 @@ tdm:
# ENU coordinate system origin (AERPAW Lake Wheeler Road Field) # ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
origin: origin:
lat: 35.72595214250436 lat: 35.72550610629396
lon: -78.69917609299937 lon: -78.70019657805574
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:
@@ -28,11 +28,11 @@ environments:
port: 5000 port: 5000
testbed: testbed:
# AERPAW testbed: E-VM listens, MAVLink Filter connects to us (UDP) # AERPAW testbed: E-VM listens, MAVLink Filter connects TO us (UDP)
mavlink: mavlink:
ip: "192.168.32.26" ip: "192.168.32.26"
port: 14550 port: 14550
# Controller runs on host machine (192.168.X.1, generally) # Controller runs on host machine (192.168.122.1 from E-VM perspective)
controller: controller:
ip: "192.168.112.1" ip: "192.168.122.1"
port: 5000 port: 5000
+2 -2
View File
@@ -1,2 +1,2 @@
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax, useDoubleIntegrator, dampingCoeff, useFixedTopology timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax
1, 100, 30.0, 0.1, 2.0, 5, 1, 1, "6.0, 6.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 5, 120, 30.0, 0.1, 1.0, 2.0, 100, 3, "3.0, 3.0", "30.0, 30.0", "80.0, 80.0", "0.25, 0.25", "5.0, 5.0", "0.1, 0.1", "0.0, 0.0, 0.0", "50.0, 50.0, 80.0", "35.0, 35.0", "10, 5, 5, 10", 0.15, "5.0, 10.0, 45.0, 15.0, 10.0, 35.0", 1, "2.0, 15.0, 0.0", "25.0, 25.0, 50.0"
1 timestep maxIter minAlt discretizationStep protectedRange initialStepSize barrierGain barrierExponent collisionRadius comRange alphaDist betaDist alphaTilt betaTilt domainMin domainMax objectivePos objectiveVar sensorPerformanceMinimum initialPositions numObstacles obstacleMin obstacleMax useDoubleIntegrator dampingCoeff useFixedTopology
2 1 5 100 120 30.0 0.1 2.0 1.0 5 2.0 1 100 1 3 6.0, 6.0 3.0, 3.0 25.0, 25.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 80.0, 80.0, 80.0 50.0, 50.0, 80.0 55.0, 55.0 35.0, 35.0 40, 25, 25, 40 10, 5, 5, 10 0.15 15.0, 10.0, 40.0, 5.0, 10.0, 45.0 5.0, 10.0, 45.0, 15.0, 10.0, 35.0 1 1.0, 25.0, 0.0 2.0, 15.0, 0.0 30.0, 30.0, 50.0 25.0, 25.0, 50.0 1 2.0 1
+120 -187
View File
@@ -133,31 +133,6 @@
<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="27" type="coderapp.internal.codertype.PrimitiveType">
<ClassName>int32</ClassName>
<Size type="coderapp.internal.codertype.Dimension"/>
<Size type="coderapp.internal.codertype.Dimension"/>
</Types>
<Types id="28" type="coderapp.internal.codertype.PrimitiveType">
<ClassName>int32</ClassName>
<Size type="coderapp.internal.codertype.Dimension"/>
<Size type="coderapp.internal.codertype.Dimension"/>
</Types>
<Types id="29" type="coderapp.internal.codertype.PrimitiveType">
<ClassName>int32</ClassName>
<Size type="coderapp.internal.codertype.Dimension"/>
<Size type="coderapp.internal.codertype.Dimension"/>
</Types>
<Types id="30" type="coderapp.internal.codertype.PrimitiveType">
<ClassName>int32</ClassName>
<Size type="coderapp.internal.codertype.Dimension"/>
<Size type="coderapp.internal.codertype.Dimension"/>
</Types>
<Types id="31" 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>
@@ -399,761 +374,719 @@
</Artifacts> </Artifacts>
<Artifacts id="40" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="40" 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/cone.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/cone.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="41" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="41" 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/cone.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/controller.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="42" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="42" 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/controller.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/controller.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="43" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="43" 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/controller.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/controller_data.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="44" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="44" 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/controller_data.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/controller_data.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="45" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="45" 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/controller_data.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/controller_initialize.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="46" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="46" 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/controller_initialize.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/controller_initialize.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="47" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="47" 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/controller_initialize.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/controller_internal_types.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="48" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="48" 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/controller_internal_types.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/controller_terminate.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="49" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="49" 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/controller_terminate.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/controller_terminate.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="50" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="50" 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/controller_terminate.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/controller_types.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="51" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="51" 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/controller_types.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/countsort.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="52" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="52" 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/countsort.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/countsort.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="53" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="53" 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/countsort.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/deleteColMoveEnd.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="54" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="54" 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/deleteColMoveEnd.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/deleteColMoveEnd.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="55" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="55" 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/deleteColMoveEnd.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/dot.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="56" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="56" 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/dot.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/dot.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="57" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="57" 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/dot.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/driver.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="58" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="58" 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/driver.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/driver.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="59" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="59" 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/driver.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/exp.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="60" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="60" 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/exp.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/exp.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="61" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="61" 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/exp.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/eye.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="62" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="62" 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/eye.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/eye.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="63" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="63" 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/eye.h</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/factorQR.cpp</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</Artifacts> </Artifacts>
<Artifacts id="64" type="coderapp.internal.build.mfz.CodegenArtifact"> <Artifacts id="64" 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/factorQR.cpp</Path> <Path>/home/kdee/Desktop/miSim/aerpaw/codegen/factorQR.h</Path>
</File> </File>
<Type>GENERATED_SOURCE</Type> <Type>GENERATED_SOURCE</Type>
</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/factorQR.h</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/feasibleX0ForWorkingSet.cpp</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.h</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/feasibleratiotest.cpp</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.h</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/find.cpp</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.h</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/fullColLDL2_.cpp</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_.h</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/guidance_step.cpp</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.h</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/iterate.cpp</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.h</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/ixamax.cpp</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.h</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/ixfun.cpp</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.h</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/lesserNeighbor.cpp</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.h</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/linearForm_.cpp</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_.h</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/maxConstraintViolation.cpp</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.h</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/meshgrid.cpp</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.h</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/miSim.cpp</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.h</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/minOrMax.cpp</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.h</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/mpower.cpp</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.h</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/nchoosek.cpp</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.h</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/norm.cpp</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.h</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/partition.cpp</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.h</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/phaseone.cpp</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.h</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/quadprog.cpp</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.h</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/ratiotest.cpp</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.h</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/rectangularPrism.cpp</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.cpp</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/sensingObjective.h</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.cpp</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/sensorPerformance.h</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.cpp</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/setProblemType.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/sigmoidSensor.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/sigmoidSensor.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/sort.cpp</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/sort.h</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/spherical.cpp</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/spherical.h</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/sprintf.cpp</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/sprintf.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/squareQ_appendCol.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/squareQ_appendCol.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/string1.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/string1.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/sum.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/sum.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/triu.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/triu.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/unique.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/unique.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/vecnorm.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/vecnorm.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/xgemv.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/xgemv.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/xgeqp3.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/xgeqp3.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/xnrm2.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/xnrm2.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/xrotg.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/xrotg.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/Desktop/miSim/aerpaw/codegen/xzgeqp3.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="159" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzgeqp3.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="160" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarf.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="161" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarf.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="162" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarfg.cpp</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="163" type="coderapp.internal.build.mfz.CodegenArtifact">
<File type="coderapp.internal.util.mfz.FileSpec">
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarfg.h</Path>
</File>
<Type>GENERATED_SOURCE</Type>
</Artifacts>
<Artifacts id="164" 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="165" 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="166" 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>
@@ -1161,7 +1094,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-04-05T13:43:54</Timestamp> <Timestamp>2026-03-03T19:58:03</Timestamp>
</MainBuildResult> </MainBuildResult>
</coderapp.internal.mlc.mfz.MatlabCoderProjectState> </coderapp.internal.mlc.mfz.MatlabCoderProjectState>
</MF0> </MF0>
+1 -24
View File
@@ -7,8 +7,7 @@ coder.extrinsic('disp', 'readScenarioCsv');
% Maximum clients supported (one initial position per UAV) % Maximum clients supported (one initial position per UAV)
MAX_CLIENTS = 4; MAX_CLIENTS = 4;
% Two waypoints per UAV: altitude-staggered transit + final position MAX_TARGETS = MAX_CLIENTS;
MAX_TARGETS = MAX_CLIENTS * 2;
% Allocate targets array (MAX_TARGETS x 3) % Allocate targets array (MAX_TARGETS x 3)
targets = zeros(MAX_TARGETS, 3); targets = zeros(MAX_TARGETS, 3);
@@ -34,28 +33,6 @@ else
numWaypoints = totalLoaded / int32(numClients); numWaypoints = totalLoaded / int32(numClients);
end end
% In the compiled path, inject altitude-staggered transit waypoints so UAVs
% are vertically separated while flying horizontally to their start positions.
% ArduPilot reaches target altitude before horizontal movement, so UAV i is at
% altitude (TRANSIT_ALT_BASE + (i-1)*TRANSIT_ALT_STEP) throughout its transit,
% preventing collisions regardless of horizontal path geometry.
% TRANSIT_ALT_STEP must exceed 2 * max(collisionRadius).
% Waypoint 1: each UAV flies to (finalX, finalY) at its unique transit altitude.
% Waypoint 2: each UAV adjusts to its actual target altitude.
if ~coder.target('MATLAB')
TRANSIT_ALT_BASE = 25.0; % must match drone.takeoff() altitude in uav_runner.py
TRANSIT_ALT_STEP = 12.1; % vertical separation per UAV (m); must exceed 2*collisionRadius
for ii = double(totalLoaded):-1:1
transitRow = (ii - 1) * 2 + 1;
finalRow = (ii - 1) * 2 + 2;
finalPos = targets(ii, :);
transitAlt = TRANSIT_ALT_BASE + (ii - 1) * TRANSIT_ALT_STEP;
targets(finalRow, :) = finalPos;
targets(transitRow, :) = [finalPos(1), finalPos(2), transitAlt];
end
numWaypoints = int32(2);
end
% Load guidance scenario from CSV (parameters for guidance_step) % Load guidance scenario from CSV (parameters for guidance_step)
NUM_SCENARIO_PARAMS = 45; NUM_SCENARIO_PARAMS = 45;
MAX_OBSTACLES_CTRL = int32(8); MAX_OBSTACLES_CTRL = int32(8);
+5 -10
View File
@@ -1,17 +1,12 @@
#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() {
// Derive numClients from initialPositions in scenario.csv // Number of clients to handle
double targets[MAX_CLIENTS_PER_PARAM * 3]; int numClients = 2; // for now
int numClients = loadInitialPositions("config/scenario.csv",
targets, MAX_CLIENTS_PER_PARAM); std::cout << "Initializing TCP server...\n";
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);
-25
View File
@@ -267,10 +267,6 @@ class CSwSNRRX(gr.top_block):
'/root/Quality', num_uavs, slot_duration, guard_interval) '/root/Quality', num_uavs, slot_duration, guard_interval)
self.blocks_file_sink_0 = TdmTaggedFileSink( self.blocks_file_sink_0 = TdmTaggedFileSink(
'/root/Power', num_uavs, slot_duration, guard_interval) '/root/Power', num_uavs, slot_duration, guard_interval)
self.blocks_file_sink_noisefloor = TdmTaggedFileSink(
'/root/NoiseFloor', num_uavs, slot_duration, guard_interval)
self._freqoffset_file = open('/root/FreqOffset', 'w')
self._freqoffset_file.write('tx_uav_id,value\n')
self.blocks_divide_xx_0 = blocks.divide_ff(1) self.blocks_divide_xx_0 = blocks.divide_ff(1)
self.blocks_complex_to_real_0_0 = blocks.complex_to_real(1) self.blocks_complex_to_real_0_0 = blocks.complex_to_real(1)
self.blocks_complex_to_real_0 = blocks.complex_to_real(1) self.blocks_complex_to_real_0 = blocks.complex_to_real(1)
@@ -314,7 +310,6 @@ class CSwSNRRX(gr.top_block):
self.connect((self.blocks_nlog10_ff_0_0, 0), (self.blocks_add_const_vxx_0, 0)) self.connect((self.blocks_nlog10_ff_0_0, 0), (self.blocks_add_const_vxx_0, 0))
self.connect((self.blocks_nlog10_ff_0_0, 0), (self.blocks_sub_xx_0, 0)) self.connect((self.blocks_nlog10_ff_0_0, 0), (self.blocks_sub_xx_0, 0))
self.connect((self.blocks_nlog10_ff_0_0_0, 0), (self.blocks_sub_xx_0, 1)) self.connect((self.blocks_nlog10_ff_0_0_0, 0), (self.blocks_sub_xx_0, 1))
self.connect((self.blocks_nlog10_ff_0_0_0, 0), (self.blocks_file_sink_noisefloor, 0))
self.connect((self.blocks_stream_to_vector_0_0, 0), (self.epy_block_0, 0)) self.connect((self.blocks_stream_to_vector_0_0, 0), (self.epy_block_0, 0))
self.connect((self.blocks_sub_xx_0, 0), (self.blocks_file_sink_0_0_0, 0)) self.connect((self.blocks_sub_xx_0, 0), (self.blocks_file_sink_0_0_0, 0))
self.connect((self.blocks_vector_to_stream_0_0, 0), (self.blocks_keep_m_in_n_0, 0)) self.connect((self.blocks_vector_to_stream_0_0, 0), (self.blocks_keep_m_in_n_0, 0))
@@ -326,26 +321,6 @@ class CSwSNRRX(gr.top_block):
self.connect((self.freq_xlating_fft_filter_ccc_0_0, 0), (self.blocks_stream_to_vector_0_0, 0)) self.connect((self.freq_xlating_fft_filter_ccc_0_0, 0), (self.blocks_stream_to_vector_0_0, 0))
self.connect((self.uhd_usrp_source_0, 0), (self.blocks_multiply_xx_0, 0)) self.connect((self.uhd_usrp_source_0, 0), (self.blocks_multiply_xx_0, 0))
##################################################
# Frequency offset polling thread
##################################################
def _freq_offset_probe():
frame_dur = slot_duration * num_uavs
while True:
val = self.digital_fll_band_edge_cc_0_0.get_frequency()
freq_hz = val * samp_rate / (2 * math.pi)
now = time.time()
slot_time = now % frame_dur
current_slot = int(slot_time / slot_duration)
time_into_slot = slot_time - current_slot * slot_duration
tx_id = -1 if time_into_slot < guard_interval else current_slot
self._freqoffset_file.write(f'{tx_id},{freq_hz}\n')
self._freqoffset_file.flush()
time.sleep(0.01)
_freq_offset_thread = threading.Thread(target=_freq_offset_probe)
_freq_offset_thread.daemon = True
_freq_offset_thread.start()
def get_args(self): def get_args(self):
return self.args return self.args
+1 -1
View File
@@ -20,4 +20,4 @@ else
fi fi
cd $PROFILE_DIR"/SDR_control/Channel_Sounderv3" 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 "$@" python3 CSwSNRRX.py --freq $RX_FREQ --gainrx $GAIN_RX --noise 0 --args $ARGS --offset $OFFSET --samp-rate $SAMP_RATE --sps $SPS
+1 -1
View File
@@ -20,4 +20,4 @@ else
fi fi
cd $PROFILE_DIR"/SDR_control/Channel_Sounderv3" 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 "$@" python3 CSwSNRTX.py --freq $TX_FREQ --gaintx $GAIN_TX --args $ARGS --offset $OFFSET --samp-rate $SAMP_RATE --sps $SPS
+2 -11
View File
@@ -1,16 +1,7 @@
#!/bin/bash #!/bin/bash
# Drop in replacements for channel sounder scripts
cp startchannelsounderRXGRC.sh /root/Profiles/ProfileScripts/Radio/Helpers/. cp startchannelsounderRXGRC.sh /root/Profiles/ProfileScripts/Radio/Helpers/.
cp startchannelsounderTXGRC.sh /root/Profiles/ProfileScripts/Radio/Helpers/. cp startchannelsounderTXGRC.sh /root/Profiles/ProfileScripts/Radio/Helpers/.
cp CSwSNRRX.py /root/Profiles/SDR_control/Channel_Sounderv3/. cp CSwSNRRX.py /root/Profiles/SDR_control/Channel_Sounderv3/.
cp CSwSNRTX.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"
echo "REMEMBER! Manually copy startVehicle_controller.sh to ~/Profiles/ProfileScripts/Vehicle/startVehicle.sh on the fixed node"
+3 -6
View File
@@ -1,8 +1,7 @@
function [f, G] = plotGpsLogs(logDirs, seaToGroundLevel, plotWholeFlight) function [f, G] = plotGpsLogs(logDirs, seaToGroundLevel)
arguments (Input) arguments (Input)
logDirs (1, 1) string; logDirs (1, 1) string;
seaToGroundLevel (1, 1) double = 110; % measured approximately from USGS national map viewer for the AERPAW test field seaToGroundLevel (1, 1) double = 110; % measured approximately from USGS national map viewer for the AERPAW test field
plotWholeFlight (1, 1) logical = false;
end end
arguments (Output) arguments (Output)
f (1, 1) matlab.ui.Figure; f (1, 1) matlab.ui.Figure;
@@ -49,10 +48,8 @@ function [f, G] = plotGpsLogs(logDirs, seaToGroundLevel, plotWholeFlight)
stopIdx = find(verticalSpeed <= prctile(verticalSpeed, pctThreshold), 1, "last"); stopIdx = find(verticalSpeed <= prctile(verticalSpeed, pctThreshold), 1, "last");
% % Plot whole flight, including setup/cleanup % % Plot whole flight, including setup/cleanup
if plotWholeFlight % startIdx = 1;
startIdx = 1; % stopIdx = length(verticalSpeed);
stopIdx = length(verticalSpeed);
end
% Convert LLA trajectory data to ENU for external analysis % Convert LLA trajectory data to ENU for external analysis
% NaN out entries outside the algorithm flight range so they don't plot % NaN out entries outside the algorithm flight range so they don't plot
+3 -12
View File
@@ -24,25 +24,16 @@ function [f, R] = plotRadioLogs(resultsPath)
R{ii}(bad, :) = []; R{ii}(bad, :) = [];
end 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 % Build legend labels and color map for up to 4 UAVs
nUAV = numel(R); nUAV = numel(R);
colors = lines(nUAV * nUAV); colors = lines(nUAV * nUAV);
styles = ["-o", "-s", "-^", "-d", "-v", "-p", "-h", "-<", "->", "-+", "-x", "-*"]; styles = ["-o", "-s", "-^", "-d", "-v", "-p", "-h", "-<", "->", "-+", "-x", "-*"];
metricNames = ["SNR", "Power", "Quality", "PathLoss", "NoiseFloor", "FreqOffset"]; metricNames = ["SNR", "Power", "Quality"];
yLabels = ["SNR (dB)", "Power (dB)", "Quality", "Path Loss (dB)", "Noise Floor (dB)", "Freq Offset (MHz)"]; yLabels = ["SNR (dB)", "Power (dB)", "Quality"];
f = figure; f = figure;
tl = tiledlayout(numel(metricNames), 1, 'TileSpacing', 'compact', 'Padding', 'compact'); tl = tiledlayout(3, 1, 'TileSpacing', 'compact', 'Padding', 'compact');
for mi = 1:numel(metricNames) for mi = 1:numel(metricNames)
ax = nexttile(tl); ax = nexttile(tl);
+13 -27
View File
@@ -4,19 +4,19 @@ function R = readRadioLogs(logPath)
end end
arguments (Output) arguments (Output)
R (:, 8) table; R (:, 6) table;
end end
% Extract receiving UAV ID from directory name (e.g. "uav0_..." 0) % Extract receiving UAV ID from directory name (e.g. "uav0_..." 0)
[~, dirName] = fileparts(logPath); [~, dirName] = fileparts(logPath);
rxID = int32(sscanf(dirName, 'uav%d')); rxID = int32(sscanf(dirName, 'uav%d'));
metrics = ["quality", "snr", "power", "noisefloor", "freqoffset"]; metrics = ["quality", "snr", "power"];
logs = dir(logPath); logs = dir(logPath);
logs = logs(endsWith({logs(:).name}, metrics + "_log.txt")); 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), ... R = table(datetime.empty(0,1), zeros(0,1,'int32'), zeros(0,1,'int32'), zeros(0,1), zeros(0,1), zeros(0,1), ...
'VariableNames', ["Timestamp", "TxUAVID", "RxUAVID", "SNR", "Power", "Quality", "NoiseFloor", "FreqOffset"]); 'VariableNames', ["Timestamp", "TxUAVID", "RxUAVID", "SNR", "Power", "Quality"]);
for ii = 1:numel(logs) for ii = 1:numel(logs)
filepath = fullfile(logs(ii).folder, logs(ii).name); filepath = fullfile(logs(ii).folder, logs(ii).name);
@@ -31,39 +31,25 @@ function R = readRadioLogs(logPath)
end end
fid = fopen(filepath, 'r'); fid = fopen(filepath, 'r');
% Skip header lines: some files have 2 tail-error lines + 1 column % Skip 3 lines: 2 junk (tail errors) + 1 header (tx_uav_id,value)
% header ("tx_uav_id,value"), others start with data immediately. for k = 1:3
% Read until a line that looks like a data record, then rewind to it. fgetl(fid);
dataPattern = '^\[\d{4}-\d{2}-\d{2} \d{2}:\d{2}:\d{2}\.\d+\] [-\d]';
linePos = ftell(fid);
while true
line = fgetl(fid);
if ~ischar(line)
break; % EOF
end
if ~isempty(regexp(line, dataPattern, 'once'))
fseek(fid, linePos, 'bof'); % rewind to start of this line
break;
end
linePos = ftell(fid);
end end
data = textscan(fid, '[%26c] %d,%f'); data = textscan(fid, '[%26c] %d,%f');
fclose(fid); fclose(fid);
ts = datetime(cellstr(data{1}), 'InputFormat', 'yyyy-MM-dd HH:mm:ss.SSSSSS'); ts = datetime(data{1}, 'InputFormat', 'yyyy-MM-dd HH:mm:ss.SSSSSS');
txId = int32(data{2}); txId = int32(data{2});
val = data{3}; val = data{3};
n = numel(ts); 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), ... t = table(ts, txId, repmat(rxID, n, 1), NaN(n,1), NaN(n,1), NaN(n,1), ...
'VariableNames', ["Timestamp", "TxUAVID", "RxUAVID", "SNR", "Power", "Quality", "NoiseFloor", "FreqOffset"]); 'VariableNames', ["Timestamp", "TxUAVID", "RxUAVID", "SNR", "Power", "Quality"]);
switch metric switch metric
case "snr", t.SNR = val; case "snr", t.SNR = val;
case "power", t.Power = val; case "power", t.Power = val;
case "quality", t.Quality = val; case "quality", t.Quality = val;
case "noisefloor", t.NoiseFloor = val;
case "freqoffset", t.FreqOffset = val;
end end
R = [R; t]; %#ok<AGROW> R = [R; t]; %#ok<AGROW>
+3 -4
View File
@@ -1,10 +1,9 @@
%% Plot AERPAW logs (trajectory, radio) %% Plot AERPAW logs (trajectory, radio)
resultsPath = fullfile(matlab.project.rootProject().RootFolder, "sandbox", "two_around_wall"); % Define path to results copied from AERPAW platform resultsPath = fullfile(matlab.project.rootProject().RootFolder, "sandbox", "t1"); % Define path to results copied from AERPAW platform
% Plot GPS logged data and scenario information (domain, objective, obstacles) % Plot GPS logged data and scenario information (domain, objective, obstacles)
seaToGroundLevel = 110; % measured approximately from USGS national map viewer seaToGroundLevel = 110; % measured approximately from USGS national map viewer
plotWholeFlight = true; % do not attempt to automatically trim initial and final positioning and landing from flight plot (buggy) [fGlobe, G] = plotGpsLogs(resultsPath, seaToGroundLevel);
% [fGlobe, G] = plotGpsLogs(resultsPath, seaToGroundLevel, true);
% Plot radio statistics % Plot radio statistics
[fRadio, R] = plotRadioLogs(resultsPath); [fRadio, R] = plotRadioLogs(resultsPath);
@@ -22,7 +21,7 @@ makeVideo = true;
% Define scenario according to CSV specification % Define scenario according to CSV specification
domain = rectangularPrism; domain = rectangularPrism;
domain = domain.initialize([params.domainMin; params.domainMax], REGION_TYPE.DOMAIN, "Domain"); domain = domain.initialize([params.domainMin; params.domainMax], REGION_TYPE.DOMAIN, "Domain");
domain.objective = domain.objective.initialize(objectiveFunctionWrapper(params.objectivePos, reshape(params.objectiveVar, [1, 2 2])), domain, params.discretizationStep, params.protectedRange, params.sensorPerformanceMinimum); 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); agents = cell(size(params.initialPositions, 2) / 3, 1);
for ii = 1:size(agents, 1) for ii = 1:size(agents, 1)
+3 -3
View File
@@ -32,8 +32,8 @@ else
exit 1 exit 1
fi fi
# Client config file: 2nd argument > AERPAW_CLIENT_CONFIG env var > default # Client config file (optional 2nd argument)
CONFIG_FILE="${2:-${AERPAW_CLIENT_CONFIG:-config/client.yaml}}" CONFIG_FILE="${2:-config/client.yaml}"
if [ ! -f "$CONFIG_FILE" ]; then if [ ! -f "$CONFIG_FILE" ]; then
echo "Error: Config file not found: $CONFIG_FILE" echo "Error: Config file not found: $CONFIG_FILE"
exit 1 exit 1
@@ -59,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 -u -m aerpawlib \ python3 -m aerpawlib \
--script client.uav_runner \ --script client.uav_runner \
--conn "$CONN" \ --conn "$CONN" \
--vehicle drone --vehicle drone
-100
View File
@@ -1,100 +0,0 @@
#!/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
View File
@@ -1,30 +0,0 @@
#!/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
View File
@@ -1,11 +0,0 @@
#!/bin/bash
cd /root/miSim/aerpaw
# Compile controller
/bin/bash compile.sh
# Run controller
./build/controller_app
cd -
-50
View File
@@ -1,50 +0,0 @@
#!/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
@@ -1,47 +0,0 @@
#!/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
@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="1" type="DIR_SIGNIFIER"/>
@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info Ref="aerpaw/scripts" Type="Relative"/>
@@ -1,2 +0,0 @@
<?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 location="1" type="DIR_SIGNIFIER"/>
@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="1" type="DIR_SIGNIFIER"/>
@@ -1,6 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info>
<Category UUID="FileClassCategory">
<Label UUID="design"/>
</Category>
</Info>
@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="initializeFromInits.m" type="File"/>
@@ -1,6 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info>
<Category UUID="FileClassCategory">
<Label UUID="design"/>
</Category>
</Info>
@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="plotFromSimHist.m" type="File"/>
@@ -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="1" type="DIR_SIGNIFIER"/>
@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="startexperiment_controller.sh" type="File"/>
@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="startRadio.sh" type="File"/>
@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="startexperiment.sh" type="File"/>
@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="startVehicle.sh" type="File"/>
@@ -1,2 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="startVehicle_controller.sh" type="File"/>
@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="1" type="DIR_SIGNIFIER"/>
@@ -1,2 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?> <?xml version="1.0" encoding="UTF-8"?>
<Info location="scripts" type="File"/> <Info/>
@@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8"?>
<Info location="test4" 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="test13" 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="t1" 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="test14" 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="test11" 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="test6" 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="test3" 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="test10" 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="test12" 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="t1.zip" 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"/>
BIN
View File
Binary file not shown.
+4 -9
View File
@@ -34,8 +34,7 @@ classdef parametricTestSuite < matlab.unittest.TestCase
% Define scenario according to CSV specification % Define scenario according to CSV specification
tc.domain = tc.domain.initialize([params.domainMin; params.domainMax], REGION_TYPE.DOMAIN, "Domain"); tc.domain = tc.domain.initialize([params.domainMin; params.domainMax], REGION_TYPE.DOMAIN, "Domain");
objectiveSigma = reshape(params.objectiveVar, [1 2 2]); tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper(params.objectivePos, reshape(params.objectiveVar, [2 2])), tc.domain, params.discretizationStep, params.protectedRange, params.sensorPerformanceMinimum);
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper(params.objectivePos, objectiveSigma), tc.domain, params.discretizationStep, params.protectedRange, params.sensorPerformanceMinimum, params.objectivePos, objectiveSigma);
agents = cell(size(params.initialPositions, 2) / 3, 1); agents = cell(size(params.initialPositions, 2) / 3, 1);
for ii = 1:size(agents, 1) for ii = 1:size(agents, 1)
@@ -58,16 +57,13 @@ classdef parametricTestSuite < matlab.unittest.TestCase
end end
% Set up simulation % Set up simulation
tc.testClass = tc.testClass.initialize(tc.domain, agents, params.barrierGain, params.barrierExponent, params.minAlt, params.timestep, params.maxIter, obstacles, tc.makePlots, tc.makeVideo, logical(params.useDoubleIntegrator), params.dampingCoeff, logical(params.useFixedTopology)); tc.testClass = tc.testClass.initialize(tc.domain, agents, params.barrierGain, params.barrierExponent, params.minAlt, params.timestep, params.maxIter, obstacles, tc.makePlots, tc.makeVideo);
% Save simulation parameters to output file % Save simulation parameters to output file
tc.testClass.writeInits(); tc.testClass.writeInits();
% Run % Run
tc.testClass = tc.testClass.run(); tc.testClass = tc.testClass.run();
% Save results and clean up
tc.testClass = tc.testClass.teardown();
end end
function csv_parametric_tests_random_agents(tc) function csv_parametric_tests_random_agents(tc)
% Read in parameters to iterate over % Read in parameters to iterate over
@@ -82,8 +78,7 @@ classdef parametricTestSuite < matlab.unittest.TestCase
for ii = 1:size(params.timestep, 1) for ii = 1:size(params.timestep, 1)
% Set up square domain % Set up square domain
tc.domain = tc.domain.initialize([zeros(1, 3); l * ones(1, 3)], REGION_TYPE.DOMAIN, "Domain"); tc.domain = tc.domain.initialize([zeros(1, 3); l * ones(1, 3)], REGION_TYPE.DOMAIN, "Domain");
objectiveCenter = [.75 * l, 0.75 * l]; tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([.75 * l, 0.75 * l]), tc.domain, params.discretizationStep(ii), params.protectedRange(ii), params.sensorPerformanceMinimum(ii));
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper(objectiveCenter), tc.domain, params.discretizationStep(ii), params.protectedRange(ii), params.sensorPerformanceMinimum(ii), objectiveCenter);
% Initialize agents % Initialize agents
agents = cell(params.numAgents(ii), 1); agents = cell(params.numAgents(ii), 1);
@@ -152,7 +147,7 @@ classdef parametricTestSuite < matlab.unittest.TestCase
end end
% randomly shuffle agents to make the network more interesting (probably) % randomly shuffle agents to make the network more interesting (probably)
agents = agents(randperm(numel(agents))); agents = agents(randperm(numel(agents)));
% Set up obstacles % Set up obstacles
obstacles = cell(params.numObstacles(ii), 1); obstacles = cell(params.numObstacles(ii), 1);
+21 -146
View File
@@ -33,8 +33,6 @@ classdef test_miSim < matlab.unittest.TestCase
initialStepSize = 0.2; % gradient ascent step size at the first iteration. Decreases linearly to 0 based on maxIter. initialStepSize = 0.2; % gradient ascent step size at the first iteration. Decreases linearly to 0 based on maxIter.
minAgents = 3; % Minimum number of agents to be randomly generated minAgents = 3; % Minimum number of agents to be randomly generated
maxAgents = 4; % Maximum number of agents to be randomly generated maxAgents = 4; % Maximum number of agents to be randomly generated
useDoubleIntegrator = false;
dampingCoeff = 2;
agents = cell(0, 1); agents = cell(0, 1);
% Collision % Collision
@@ -54,7 +52,6 @@ classdef test_miSim < matlab.unittest.TestCase
sensor = sigmoidSensor; sensor = sigmoidSensor;
% Communications % Communications
useFixedTopology = false;
minCommsRange = 3; % Minimum randomly generated collision geometry size minCommsRange = 3; % Minimum randomly generated collision geometry size
maxCommsRange = 5; % Maximum randomly generated collision geometry size maxCommsRange = 5; % Maximum randomly generated collision geometry size
commsRanges = NaN; commsRanges = NaN;
@@ -166,8 +163,8 @@ classdef test_miSim < matlab.unittest.TestCase
end end
% Initialize candidate agent collision geometry % Initialize candidate agent collision geometry
candidateGeometry = spherical; candidateGeometry = rectangularPrism;
candidateGeometry = candidateGeometry.initialize(candidatePos, tc.collisionRanges(ii), REGION_TYPE.COLLISION); candidateGeometry = candidateGeometry.initialize([candidatePos - tc.collisionRanges(ii) * ones(1, 3); candidatePos + tc.collisionRanges(ii) * ones(1, 3)], REGION_TYPE.COLLISION);
% Initialize candidate agent sensor model % Initialize candidate agent sensor model
tc.sensor = tc.sensor.initialize(tc.alphaDistMin + rand * (tc.alphaDistMax - tc.alphaDistMin), tc.betaDistMin + rand * (tc.betaDistMax - tc.betaDistMin), tc.alphaTiltMin + rand * (tc.alphaTiltMax - tc.alphaTiltMin), tc.betaTiltMin + rand * (tc.betaTiltMax - tc.betaTiltMin)); tc.sensor = tc.sensor.initialize(tc.alphaDistMin + rand * (tc.alphaDistMax - tc.alphaDistMin), tc.betaDistMin + rand * (tc.betaDistMax - tc.betaDistMin), tc.alphaTiltMin + rand * (tc.alphaTiltMax - tc.alphaTiltMin), tc.betaTiltMin + rand * (tc.betaTiltMax - tc.betaTiltMin));
@@ -227,7 +224,7 @@ classdef test_miSim < matlab.unittest.TestCase
end end
% Initialize the simulation % Initialize the simulation
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
end end
function miSim_run(tc) function miSim_run(tc)
% randomly create obstacles % randomly create obstacles
@@ -366,7 +363,7 @@ classdef test_miSim < matlab.unittest.TestCase
end end
% Initialize the simulation % Initialize the simulation
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
% Write out initialization state % Write out initialization state
tc.testClass.writeInits(); tc.testClass.writeInits();
@@ -400,7 +397,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.obstacles = cell(0, 1); tc.obstacles = cell(0, 1);
tc.makePlots = false; tc.makePlots = false;
tc.makeVideo = false; tc.makeVideo = false;
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
centerIdx = floor(size(tc.testClass.partitioning, 1) / 2); centerIdx = floor(size(tc.testClass.partitioning, 1) / 2);
tc.verifyEqual(tc.testClass.partitioning(centerIdx, centerIdx:(centerIdx + 2)), [2, 3, 1]); % all three near center tc.verifyEqual(tc.testClass.partitioning(centerIdx, centerIdx:(centerIdx + 2)), [2, 3, 1]); % all three near center
@@ -425,7 +422,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.obstacles = cell(0, 1); tc.obstacles = cell(0, 1);
tc.makePlots = false; tc.makePlots = false;
tc.makeVideo = false; tc.makeVideo = false;
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
close(tc.testClass.fPerf); close(tc.testClass.fPerf);
tc.verifyEqual(unique(tc.testClass.partitioning), [0; 1]); tc.verifyEqual(unique(tc.testClass.partitioning), [0; 1]);
@@ -437,12 +434,12 @@ classdef test_miSim < matlab.unittest.TestCase
tc.domain = tc.domain.initialize([zeros(1, 3);tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain"); tc.domain = tc.domain.initialize([zeros(1, 3);tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain");
% make basic sensing objective % make basic sensing objective
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([7, 6]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [7, 6]); tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([7, 6]), tc.domain, tc.discretizationStep, tc.protectedRange);
% Initialize agent collision geometry % Initialize agent collision geometry
tc.agents = {agent}; tc.agents = {agent};
geometry1 = spherical; geometry1 = rectangularPrism;
geometry1 = geometry1.initialize([tc.domain.center(1:2)-tc.domain.dimensions(1)/4, 3], tc.collisionRanges(1), REGION_TYPE.COLLISION); geometry1 = geometry1.initialize([[tc.domain.center(1:2)-tc.domain.dimensions(1)/4, 3] - tc.collisionRanges(1) * ones(1, 3); [tc.domain.center(1:2)-tc.domain.dimensions(1)/4, 3] + tc.collisionRanges(1) * ones(1, 3)], REGION_TYPE.COLLISION);
% Initialize agent sensor model with fixed parameters % Initialize agent sensor model with fixed parameters
tc.sensor = tc.sensor.initialize(tc.minDimension / 2, 3, 20, 3); tc.sensor = tc.sensor.initialize(tc.minDimension / 2, 3, 20, 3);
@@ -453,7 +450,7 @@ classdef test_miSim < matlab.unittest.TestCase
% Initialize the simulation % Initialize the simulation
tc.obstacles = cell(0, 1); tc.obstacles = cell(0, 1);
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
% Run the simulation % Run the simulation
tc.testClass = tc.testClass.run();end tc.testClass = tc.testClass.run();end
@@ -466,7 +463,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.domain = tc.domain.initialize([zeros(1, 3);tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain"); tc.domain = tc.domain.initialize([zeros(1, 3);tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain");
% make basic sensing objective % make basic sensing objective
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([3, 7]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [3, 7]); tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([3, 7]), tc.domain, tc.discretizationStep, tc.protectedRange);
% Initialize agent collision geometry % Initialize agent collision geometry
tc.agents = {agent; agent}; tc.agents = {agent; agent};
@@ -488,7 +485,7 @@ classdef test_miSim < matlab.unittest.TestCase
% Initialize the simulation % Initialize the simulation
tc.obstacles = cell(0, 1); tc.obstacles = cell(0, 1);
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
% Run the simulation % Run the simulation
tc.testClass.run(); tc.testClass.run();
@@ -504,7 +501,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.domain = tc.domain.initialize([zeros(1, 3);tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain"); tc.domain = tc.domain.initialize([zeros(1, 3);tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain");
% make basic sensing objective % make basic sensing objective
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5.2195]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [8, 5.2195]); tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5.2195]), tc.domain, tc.discretizationStep, tc.protectedRange);
% Initialize agent collision geometry % Initialize agent collision geometry
tc.agents = {agent; agent;}; tc.agents = {agent; agent;};
@@ -534,7 +531,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.agents{2} = tc.agents{2}.initialize(tc.domain.center - d - [0, tc.collisionRanges(2) *1.1 + yOffset, 0], geometry2, tc.sensor, tc.commsRanges(2), tc.maxIter, tc.initialStepSize); tc.agents{2} = tc.agents{2}.initialize(tc.domain.center - d - [0, tc.collisionRanges(2) *1.1 + yOffset, 0], geometry2, tc.sensor, tc.commsRanges(2), tc.maxIter, tc.initialStepSize);
% Initialize the simulation % Initialize the simulation
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
% Run the simulation % Run the simulation
tc.testClass.run(); tc.testClass.run();
@@ -574,7 +571,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.agents{2} = tc.agents{2}.initialize(tc.domain.center - d, geometry2, tc.sensor, tc.commsRanges(2), tc.maxIter, tc.initialStepSize); tc.agents{2} = tc.agents{2}.initialize(tc.domain.center - d, geometry2, tc.sensor, tc.commsRanges(2), tc.maxIter, tc.initialStepSize);
% Initialize the simulation % Initialize the simulation
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
% Run the simulation % Run the simulation
tc.testClass = tc.testClass.run(); tc.testClass = tc.testClass.run();
@@ -588,7 +585,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.domain = tc.domain.initialize([zeros(1, 3); tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain"); tc.domain = tc.domain.initialize([zeros(1, 3); tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain");
% make basic sensing objective % make basic sensing objective
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [8, 5]); tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5]), tc.domain, tc.discretizationStep, tc.protectedRange);
% Initialize agent collision geometry % Initialize agent collision geometry
tc.agents = {agent; agent;}; tc.agents = {agent; agent;};
@@ -617,7 +614,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.minAlt = 0; tc.minAlt = 0;
tc.makePlots = false; tc.makePlots = false;
tc.makeVideo = false; tc.makeVideo = false;
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
% Communications link should be established % Communications link should be established
tc.assertEqual(tc.testClass.adjacency, logical(true(2))); tc.assertEqual(tc.testClass.adjacency, logical(true(2)));
@@ -633,7 +630,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.domain = tc.domain.initialize([zeros(1, 3);tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain"); tc.domain = tc.domain.initialize([zeros(1, 3);tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain");
% make basic sensing objective % make basic sensing objective
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [8, 5]); tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5]), tc.domain, tc.discretizationStep, tc.protectedRange);
% Initialize agent collision geometry % Initialize agent collision geometry
tc.agents = {agent; agent; agent; agent; agent;}; tc.agents = {agent; agent; agent; agent; agent;};
@@ -662,7 +659,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.minAlt = 0; tc.minAlt = 0;
tc.makePlots = false; tc.makePlots = false;
tc.makeVideo = false; tc.makeVideo = false;
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
% Constraint adjacency matrix defined by LNA should be as follows % Constraint adjacency matrix defined by LNA should be as follows
tc.assertEqual(tc.testClass.constraintAdjacencyMatrix, logical( ... tc.assertEqual(tc.testClass.constraintAdjacencyMatrix, logical( ...
@@ -683,7 +680,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.domain = tc.domain.initialize([zeros(1, 3); tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain"); tc.domain = tc.domain.initialize([zeros(1, 3); tc.minDimension* ones(1, 3)], REGION_TYPE.DOMAIN, "Domain");
% make basic sensing objective % make basic sensing objective
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [8, 5]); tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5]), tc.domain, tc.discretizationStep, tc.protectedRange);
% Initialize agent collision geometry % Initialize agent collision geometry
tc.agents = {agent; agent; agent; agent; agent; agent; agent;}; tc.agents = {agent; agent; agent; agent; agent; agent; agent;};
@@ -716,7 +713,7 @@ classdef test_miSim < matlab.unittest.TestCase
tc.minAlt = 0; tc.minAlt = 0;
tc.makePlots = false; tc.makePlots = false;
tc.makeVideo = false; tc.makeVideo = false;
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology); tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
% Constraint adjacency matrix defined by LNA should be as follows % Constraint adjacency matrix defined by LNA should be as follows
tc.assertEqual(tc.testClass.constraintAdjacencyMatrix, logical( ... tc.assertEqual(tc.testClass.constraintAdjacencyMatrix, logical( ...
@@ -728,128 +725,6 @@ classdef test_miSim < matlab.unittest.TestCase
0, 0, 0, 1, 1, 1, 1; 0, 0, 0, 1, 1, 1, 1;
0, 0, 0, 0, 0, 1, 1; ])); 0, 0, 0, 0, 0, 1, 1; ]));
end end
function miSim_initializeFromInits(tc)
% Build a minimal valid simulation, write it to a matfile, reload
% via initializeFromInits, assert round-trip consistency, then
% delete the file. No plotting or video at any stage.
% Obstacles
nGeom = tc.minNumObstacles + randi(tc.maxNumObstacles - tc.minNumObstacles);
tc.obstacles = cell(nGeom, 1);
for ii = 1:nGeom
badCandidate = true;
while badCandidate
tc.obstacles{ii} = rectangularPrism;
tc.obstacles{ii} = tc.obstacles{ii}.initializeRandom(REGION_TYPE.OBSTACLE, ...
sprintf("Obstacle %d", ii), tc.minObstacleSize, tc.maxObstacleSize, ...
tc.domain, tc.minAlt);
if ~tc.obstacleCollisionCheck(tc.obstacles(1:(ii - 1)), tc.obstacles{ii})
badCandidate = false;
end
end
end
% Agents
nAgents = tc.minAgents;
tc.agents = cell(nAgents, 1);
tc.collisionRanges = tc.minCollisionRange + rand(nAgents, 1) * (tc.maxCollisionRange - tc.minCollisionRange);
tc.commsRanges = tc.minCommsRange + rand(nAgents, 1) * (tc.maxCommsRange - tc.minCommsRange);
for ii = 1:nAgents
initInvalid = true;
while initInvalid
if ii == 1
candidatePos = tc.domain.random();
candidatePos(3) = tc.minAlt + rand * 3;
while agentsCrowdObjective(tc.domain.objective, candidatePos, mean(tc.domain.dimensions) / 2)
candidatePos = tc.domain.random();
candidatePos(3) = tc.minAlt + rand * 3;
end
else
candidatePos = tc.agents{randi(ii - 1)}.pos + sign(randn([1, 3])) .* (rand(1, 3) .* tc.commsRanges(ii) / sqrt(2));
candidatePos(3) = tc.minAlt + rand * 3;
end
if ~tc.domain.contains(candidatePos), continue; end
if agentsCrowdObjective(tc.domain.objective, candidatePos, mean(tc.domain.dimensions) / 2), continue; end
% Connectivity check
connections = false(1, ii - 1);
for jj = 1:(ii - 1)
if norm(tc.agents{jj}.pos - candidatePos) <= min(tc.commsRanges([ii, jj]))
connections(jj) = true;
for kk = 1:size(tc.obstacles, 1)
if tc.obstacles{kk}.containsLine(tc.agents{jj}.pos, candidatePos)
connections(jj) = false;
end
end
end
end
if ii ~= 1 && ~any(connections), continue; end
geom = spherical;
geom = geom.initialize(candidatePos, tc.collisionRanges(ii), REGION_TYPE.COLLISION);
tc.sensor = sigmoidSensor;
tc.sensor = tc.sensor.initialize( ...
tc.alphaDistMin + rand * (tc.alphaDistMax - tc.alphaDistMin), ...
tc.betaDistMin + rand * (tc.betaDistMax - tc.betaDistMin), ...
tc.alphaTiltMin + rand * (tc.alphaTiltMax - tc.alphaTiltMin), ...
tc.betaTiltMin + rand * (tc.betaTiltMax - tc.betaTiltMin));
newAgent = agent;
newAgent = newAgent.initialize(candidatePos, geom, tc.sensor, tc.commsRanges(ii), tc.maxIter, tc.initialStepSize);
% Domain / obstacle / agent collision checks
violation = false;
for jj = 1:size(newAgent.collisionGeometry.vertices, 1)
if ~tc.domain.contains(newAgent.collisionGeometry.vertices(jj, 1:3))
violation = true; break;
end
end
if violation, continue; end
for kk = 1:size(tc.obstacles, 1)
if geometryIntersects(tc.obstacles{kk}, newAgent.collisionGeometry)
violation = true; break;
end
end
if violation, continue; end
for kk = 1:(ii - 1)
if geometryIntersects(tc.agents{kk}.collisionGeometry, newAgent.collisionGeometry)
violation = true; break;
end
end
if newAgent.pos(3) - newAgent.collisionGeometry.radius <= tc.minAlt
violation = true;
end
if violation, continue; end
initInvalid = false;
tc.agents{ii} = newAgent;
end
end
% Initialize first sim (no plots / video)
sim1 = miSim;
sim1 = sim1.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, ...
tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, false, false, ...
tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
% Write inits and build file path
sim1.writeInits();
initsFile = fullfile(matlab.project.rootProject().RootFolder, "sandbox", ...
strcat(sim1.artifactName, "_miSimInits.mat"));
% Load via initializeFromInits
sim2 = miSim;
sim2 = sim2.initializeFromInits(initsFile);
% Assertions
tc.assertEqual(size(sim2.agents, 1), size(sim1.agents, 1));
tc.assertEqual(sim2.maxIter, sim1.maxIter);
tc.assertEqual(sim2.barrierGain, sim1.barrierGain);
% Cleanup
delete(initsFile);
end
end end
methods methods
+3 -3
View File
@@ -4,12 +4,12 @@ function f = objectiveFunctionWrapper(center, sigma)
% composite objectives in particular % composite objectives in particular
arguments (Input) arguments (Input)
center (:, 2) double; center (:, 2) double;
sigma (:, 2, 2) double = eye(2); sigma (2, 2) double = eye(2);
end end
arguments (Output) arguments (Output)
f (1, 1) {mustBeA(f, "function_handle")}; f (1, 1) {mustBeA(f, "function_handle")};
end end
assert(size(center, 1) == size(sigma, 1)); f = @(x,y) sum(cell2mat(arrayfun(@(i) mvnpdf([x(:), y(:)], center(i,:), sigma), 1:size(center,1), "UniformOutput", false)), 2);
f = @(x,y) sum(cell2mat(arrayfun(@(i) mvnpdf([x(:), y(:)], center(i,:), squeeze(sigma(i, :, :))), 1:size(center,1), "UniformOutput", false)), 2);
end end