Compare commits
24 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| a30dfe6be7 | |||
| 9c65bf7880 | |||
| fbcaa32abd | |||
| 09a10abfd5 | |||
| 87060ca123 | |||
| f7902ee220 | |||
| 5c90219322 | |||
| d3bdc80e64 | |||
| f3f9ec3db2 | |||
| 9564a5707f | |||
| 789aecc560 | |||
| bd452b7180 | |||
| 31e88a8535 | |||
| f598a832fa | |||
| ac09a59c00 | |||
| 7a3fcbd4dc | |||
| 8db6c70f46 | |||
| 43229a3a09 | |||
| 3b3cab2089 | |||
| b7bb2dec53 | |||
| 60475162e4 | |||
| 8da65278a2 | |||
| 0bcdd73882 | |||
| c3fa1de914 |
@@ -4,6 +4,7 @@
|
|||||||
*.autosave
|
*.autosave
|
||||||
*.slx.r*
|
*.slx.r*
|
||||||
*.mdl.r*
|
*.mdl.r*
|
||||||
|
*.bak
|
||||||
|
|
||||||
# Derived content-obscured files
|
# Derived content-obscured files
|
||||||
*.p
|
*.p
|
||||||
@@ -48,6 +49,7 @@ sandbox/*
|
|||||||
|
|
||||||
# Figures
|
# Figures
|
||||||
*.fig
|
*.fig
|
||||||
|
*.png
|
||||||
|
|
||||||
# Python Virtual Environment
|
# Python Virtual Environment
|
||||||
aerpaw/venv/
|
aerpaw/venv/
|
||||||
|
|||||||
@@ -15,6 +15,7 @@ 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.vel = zeros(1, 3);
|
||||||
obj.lastVel = zeros(1, 3);
|
obj.lastVel = zeros(1, 3);
|
||||||
obj.collisionGeometry = collisionGeometry;
|
obj.collisionGeometry = collisionGeometry;
|
||||||
|
|||||||
+7
-2
@@ -14,6 +14,13 @@ function obj = run(obj, domain, partitioning, timestepIndex, index, agents, useD
|
|||||||
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(:))
|
||||||
@@ -79,10 +86,8 @@ function obj = run(obj, domain, partitioning, timestepIndex, index, agents, useD
|
|||||||
gradNorm = norm(gradC);
|
gradNorm = norm(gradC);
|
||||||
|
|
||||||
% Compute unconstrained next state
|
% Compute unconstrained next state
|
||||||
obj.lastPos = obj.pos;
|
|
||||||
if useDoubleIntegrator
|
if useDoubleIntegrator
|
||||||
% Double-integrator: gradient produces desired acceleration with damping
|
% Double-integrator: gradient produces desired acceleration with damping
|
||||||
obj.lastVel = obj.vel;
|
|
||||||
if gradNorm < 1e-100
|
if gradNorm < 1e-100
|
||||||
a_gradient = zeros(1, 3);
|
a_gradient = zeros(1, 3);
|
||||||
else
|
else
|
||||||
|
|||||||
+23
-19
@@ -39,10 +39,10 @@ function [obj] = constrainMotion(obj)
|
|||||||
h(logical(eye(nAgents))) = 0; % self value is 0
|
h(logical(eye(nAgents))) = 0; % self value is 0
|
||||||
for ii = 1:(nAgents - 1)
|
for ii = 1:(nAgents - 1)
|
||||||
for jj = (ii + 1):nAgents
|
for jj = (ii + 1):nAgents
|
||||||
h(ii, jj) = norm(obj.agents{ii}.pos - obj.agents{jj}.pos)^2 - (obj.agents{ii}.collisionGeometry.radius + obj.agents{jj}.collisionGeometry.radius)^2;
|
h(ii, jj) = norm(obj.agents{ii}.lastPos - obj.agents{jj}.lastPos)^2 - (obj.agents{ii}.collisionGeometry.radius + obj.agents{jj}.collisionGeometry.radius)^2;
|
||||||
h(jj, ii) = h(ii, jj);
|
h(jj, ii) = h(ii, jj);
|
||||||
|
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.pos - obj.agents{jj}.pos);
|
A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.lastPos - obj.agents{jj}.lastPos);
|
||||||
A(kk, (3 * jj - 2):(3 * jj)) = -A(kk, (3 * ii - 2):(3 * ii));
|
A(kk, (3 * jj - 2):(3 * jj)) = -A(kk, (3 * ii - 2):(3 * ii));
|
||||||
% Slack derived from existing params: recovery velocity = max gradient approach velocity.
|
% Slack derived from existing params: recovery velocity = max gradient approach velocity.
|
||||||
% Correction splits between 2 agents, so |A| = 2*r_sum
|
% Correction splits between 2 agents, so |A| = 2*r_sum
|
||||||
@@ -61,7 +61,9 @@ function [obj] = constrainMotion(obj)
|
|||||||
end
|
end
|
||||||
|
|
||||||
idx = length(h(triu(true(size(h)), 1)));
|
idx = length(h(triu(true(size(h)), 1)));
|
||||||
|
if coder.target('MATLAB')
|
||||||
obj.barriers(1:idx, obj.timestepIndex) = h(triu(true(size(h)), 1));
|
obj.barriers(1:idx, obj.timestepIndex) = h(triu(true(size(h)), 1));
|
||||||
|
end
|
||||||
idx = idx + 1;
|
idx = idx + 1;
|
||||||
|
|
||||||
hObs = NaN(nAgents, size(obj.obstacles, 1));
|
hObs = NaN(nAgents, size(obj.obstacles, 1));
|
||||||
@@ -69,11 +71,11 @@ function [obj] = constrainMotion(obj)
|
|||||||
for ii = 1:nAgents
|
for ii = 1:nAgents
|
||||||
for jj = 1:size(obj.obstacles, 1)
|
for jj = 1:size(obj.obstacles, 1)
|
||||||
% find closest position to agent on/in obstacle
|
% find closest position to agent on/in obstacle
|
||||||
cPos = obj.obstacles{jj}.closestToPoint(obj.agents{ii}.pos);
|
cPos = obj.obstacles{jj}.closestToPoint(obj.agents{ii}.lastPos);
|
||||||
|
|
||||||
hObs(ii, jj) = dot(obj.agents{ii}.pos - cPos, obj.agents{ii}.pos - cPos) - obj.agents{ii}.collisionGeometry.radius^2;
|
hObs(ii, jj) = dot(obj.agents{ii}.lastPos - cPos, obj.agents{ii}.lastPos - cPos) - obj.agents{ii}.collisionGeometry.radius^2;
|
||||||
|
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.pos - cPos);
|
A(kk, (3 * ii - 2):(3 * ii)) = -2 * (obj.agents{ii}.lastPos - cPos);
|
||||||
% Floor for single-agent constraint: full correction on one agent, |A| = 2*r_i
|
% Floor for single-agent constraint: full correction on one agent, |A| = 2*r_i
|
||||||
r_i = obj.agents{ii}.collisionGeometry.radius;
|
r_i = obj.agents{ii}.collisionGeometry.radius;
|
||||||
v_max_i = obj.agents{ii}.initialStepSize / obj.timestep;
|
v_max_i = obj.agents{ii}.initialStepSize / obj.timestep;
|
||||||
@@ -84,7 +86,9 @@ function [obj] = constrainMotion(obj)
|
|||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
if coder.target('MATLAB')
|
||||||
obj.barriers(idx:(idx + numel(hObs) - 1), obj.timestepIndex) = reshape(hObs, [], 1);
|
obj.barriers(idx:(idx + numel(hObs) - 1), obj.timestepIndex) = reshape(hObs, [], 1);
|
||||||
|
end
|
||||||
idx = idx + numel(hObs);
|
idx = idx + numel(hObs);
|
||||||
|
|
||||||
% Set up domain constraints (walls and ceiling only)
|
% Set up domain constraints (walls and ceiling only)
|
||||||
@@ -93,48 +97,45 @@ function [obj] = constrainMotion(obj)
|
|||||||
h_xMin = 0.0; h_xMax = 0.0; h_yMin = 0.0; h_yMax = 0.0; h_zMin = 0.0; h_zMax = 0.0;
|
h_xMin = 0.0; h_xMax = 0.0; h_yMin = 0.0; h_yMax = 0.0; h_zMin = 0.0; h_zMax = 0.0;
|
||||||
for ii = 1:nAgents
|
for ii = 1:nAgents
|
||||||
% X minimum
|
% X minimum
|
||||||
h_xMin = (obj.agents{ii}.pos(1) - obj.domain.minCorner(1)) - obj.agents{ii}.collisionGeometry.radius;
|
h_xMin = (obj.agents{ii}.lastPos(1) - obj.domain.minCorner(1)) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [-1, 0, 0];
|
A(kk, (3 * ii - 2):(3 * ii)) = [-1, 0, 0];
|
||||||
b(kk) = obj.barrierGain * max(0, h_xMin)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_xMin)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
% X maximum
|
% X maximum
|
||||||
h_xMax = (obj.domain.maxCorner(1) - obj.agents{ii}.pos(1)) - obj.agents{ii}.collisionGeometry.radius;
|
h_xMax = (obj.domain.maxCorner(1) - obj.agents{ii}.lastPos(1)) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [1, 0, 0];
|
A(kk, (3 * ii - 2):(3 * ii)) = [1, 0, 0];
|
||||||
b(kk) = obj.barrierGain * max(0, h_xMax)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_xMax)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
% Y minimum
|
% Y minimum
|
||||||
h_yMin = (obj.agents{ii}.pos(2) - obj.domain.minCorner(2)) - obj.agents{ii}.collisionGeometry.radius;
|
h_yMin = (obj.agents{ii}.lastPos(2) - obj.domain.minCorner(2)) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [0, -1, 0];
|
A(kk, (3 * ii - 2):(3 * ii)) = [0, -1, 0];
|
||||||
b(kk) = obj.barrierGain * max(0, h_yMin)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_yMin)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
% Y maximum
|
% Y maximum
|
||||||
h_yMax = (obj.domain.maxCorner(2) - obj.agents{ii}.pos(2)) - obj.agents{ii}.collisionGeometry.radius;
|
h_yMax = (obj.domain.maxCorner(2) - obj.agents{ii}.lastPos(2)) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [0, 1, 0];
|
A(kk, (3 * ii - 2):(3 * ii)) = [0, 1, 0];
|
||||||
b(kk) = obj.barrierGain * max(0, h_yMax)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_yMax)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
% Z minimum — enforce z >= minAlt + radius (not just z >= domain floor + radius)
|
% Z minimum — enforce z >= minAlt + radius (not just z >= domain floor + radius)
|
||||||
h_zMin = (obj.agents{ii}.pos(3) - obj.minAlt) - obj.agents{ii}.collisionGeometry.radius;
|
h_zMin = (obj.agents{ii}.lastPos(3) - obj.minAlt) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [0, 0, -1];
|
A(kk, (3 * ii - 2):(3 * ii)) = [0, 0, -1];
|
||||||
b(kk) = obj.barrierGain * max(0, h_zMin)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_zMin)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
% Z maximum
|
% Z maximum
|
||||||
h_zMax = (obj.domain.maxCorner(3) - obj.agents{ii}.pos(3)) - obj.agents{ii}.collisionGeometry.radius;
|
h_zMax = (obj.domain.maxCorner(3) - obj.agents{ii}.lastPos(3)) - obj.agents{ii}.collisionGeometry.radius;
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = [0, 0, 1];
|
A(kk, (3 * ii - 2):(3 * ii)) = [0, 0, 1];
|
||||||
b(kk) = obj.barrierGain * max(0, h_zMax)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_zMax)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
obj.barriers(idx:(idx + 5), obj.timestepIndex) = [h_xMin; h_xMax; h_yMin; h_yMax; h_zMin; h_zMax];
|
|
||||||
idx = idx + 6;
|
|
||||||
end
|
|
||||||
|
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
% Save off h function values (logging only — not needed in compiled mode)
|
obj.barriers(idx:(idx + 5), obj.timestepIndex) = [h_xMin; h_xMax; h_yMin; h_yMax; h_zMin; h_zMax];
|
||||||
obj.h(:, obj.timestepIndex) = [h(triu(true(nAgents), 1)); reshape(hObs, [], 1); h_xMin; h_xMax; h_yMin; h_yMax; h_zMin; h_zMax;];
|
end
|
||||||
|
idx = idx + 6;
|
||||||
end
|
end
|
||||||
|
|
||||||
% Add communication network constraints
|
% Add communication network constraints
|
||||||
@@ -145,9 +146,9 @@ function [obj] = constrainMotion(obj)
|
|||||||
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
|
paddingFactor = 0.9; % Barrier at 90% of actual range; real comms still work beyond this
|
||||||
r_comms = paddingFactor * min([obj.agents{ii}.commsGeometry.radius, obj.agents{jj}.commsGeometry.radius]);
|
r_comms = paddingFactor * min([obj.agents{ii}.commsGeometry.radius, obj.agents{jj}.commsGeometry.radius]);
|
||||||
hComms(ii, jj) = r_comms^2 - norm(obj.agents{ii}.pos - obj.agents{jj}.pos)^2;
|
hComms(ii, jj) = r_comms^2 - norm(obj.agents{ii}.lastPos - obj.agents{jj}.lastPos)^2;
|
||||||
|
|
||||||
A(kk, (3 * ii - 2):(3 * ii)) = 2 * (obj.agents{ii}.pos - obj.agents{jj}.pos);
|
A(kk, (3 * ii - 2):(3 * ii)) = 2 * (obj.agents{ii}.lastPos - obj.agents{jj}.lastPos);
|
||||||
A(kk, (3 * jj - 2):(3 * jj)) = -A(kk, (3 * ii - 2):(3 * ii));
|
A(kk, (3 * jj - 2):(3 * jj)) = -A(kk, (3 * ii - 2):(3 * ii));
|
||||||
|
|
||||||
% One-step forward invariance: b = h/dt ensures h cannot
|
% One-step forward invariance: b = h/dt ensures h cannot
|
||||||
@@ -164,7 +165,10 @@ function [obj] = constrainMotion(obj)
|
|||||||
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));
|
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.
|
% Double-integrator: transform QP from velocity to acceleration space.
|
||||||
% Single-integrator constraint: A * v <= b
|
% Single-integrator constraint: A * v <= b
|
||||||
|
|||||||
+6
-2
@@ -109,8 +109,6 @@ 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
|
||||||
@@ -138,6 +136,12 @@ function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, m
|
|||||||
% Initialize variable that will store barrier function values per timestep for analysis purposes
|
% Initialize variable that will store barrier function values per timestep for analysis purposes
|
||||||
obj.barriers = NaN(obj.numBarriers, size(obj.times, 1));
|
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();
|
||||||
|
|
||||||
|
|||||||
@@ -0,0 +1,87 @@
|
|||||||
|
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
|
||||||
+4
-4
@@ -7,7 +7,6 @@ classdef miSim
|
|||||||
timestepIndex = NaN; % index of the current timestep (useful for time-indexed arrays)
|
timestepIndex = NaN; % index of the current timestep (useful for time-indexed arrays)
|
||||||
maxIter = NaN; % maximum number of simulation iterations
|
maxIter = NaN; % maximum number of simulation iterations
|
||||||
domain;
|
domain;
|
||||||
objective;
|
|
||||||
obstacles; % geometries that define obstacles within the domain
|
obstacles; % geometries that define obstacles within the domain
|
||||||
agents; % agents that move within the domain
|
agents; % agents that move within the domain
|
||||||
adjacency = false(0, 0); % Adjacency matrix representing communications network graph
|
adjacency = false(0, 0); % Adjacency matrix representing communications network graph
|
||||||
@@ -28,6 +27,7 @@ classdef miSim
|
|||||||
spatialPlotIndices = [6, 4, 3, 2];
|
spatialPlotIndices = [6, 4, 3, 2];
|
||||||
numBarriers = 0; % Number of barrier functions needed
|
numBarriers = 0; % Number of barrier functions needed
|
||||||
barriers = []; % log barrier function values at each timestep for analysis
|
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)
|
||||||
@@ -54,7 +54,6 @@ 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
|
||||||
@@ -67,12 +66,13 @@ 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, useDoubleIntegrator, dampingCoeff, useFixedTopology);
|
||||||
[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);
|
||||||
|
|||||||
@@ -0,0 +1,93 @@
|
|||||||
|
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
|
||||||
+13
-4
@@ -6,6 +6,10 @@ 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");
|
||||||
|
|
||||||
@@ -15,7 +19,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.h(1:(size(obj.agents, 1) * (size(obj.agents, 1) - 1) / 2), :)');
|
obj.caPlot = plot(obj.barriers(1:nCA, :)');
|
||||||
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)
|
||||||
@@ -31,7 +35,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.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)), :)');
|
obj.obsPlot = plot(obj.barriers((nCA + 1):(nCA + nObs), :)');
|
||||||
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)
|
||||||
@@ -47,8 +51,13 @@ 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.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)');
|
obj.domPlot = plot(obj.barriers((nCA + nObs + 1):(nCA + nObs + nDom), :)');
|
||||||
legend(obj.hf.Children(1).Children(1), ["X Min"; "X Max"; "Y Min"; "Y Max"; "Z Min"; "Z Max";], "Location", "bestoutside");
|
domLabels = ["X Min", "X Max", "Y Min", "Y Max", "Z Min", "Z Max"];
|
||||||
|
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));
|
||||||
|
|||||||
@@ -11,6 +11,10 @@ function [obj] = run(obj)
|
|||||||
if obj.makeVideo
|
if obj.makeVideo
|
||||||
v = obj.setupVideoWriter();
|
v = obj.setupVideoWriter();
|
||||||
v.open();
|
v.open();
|
||||||
|
|
||||||
|
% Write initialization state frame in to video
|
||||||
|
I = getframe(obj.f);
|
||||||
|
v.writeVideo(I);
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
@@ -34,6 +38,11 @@ function [obj] = run(obj)
|
|||||||
obj = obj.lesserNeighbor();
|
obj = obj.lesserNeighbor();
|
||||||
end
|
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)
|
||||||
|
|||||||
+2
-1
@@ -20,6 +20,7 @@ function obj = teardown(obj)
|
|||||||
out.dampingCoeff = obj.dampingCoeff;
|
out.dampingCoeff = obj.dampingCoeff;
|
||||||
out.useDoubleIntegrator = obj.useDoubleIntegrator;
|
out.useDoubleIntegrator = obj.useDoubleIntegrator;
|
||||||
out.useFixedTopology = obj.useFixedTopology;
|
out.useFixedTopology = obj.useFixedTopology;
|
||||||
|
out.constraintAdjacency = obj.constraintAdjacencyHist(:, :, 1:(end - 1));
|
||||||
for ii = 1:size(obj.agents, 1)
|
for ii = 1:size(obj.agents, 1)
|
||||||
out.agent(ii).pos = squeeze(obj.posHist(ii, 1:(end - 1), 1:3));
|
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).vel = squeeze(obj.velHist(ii, 1:(end - 1), 1:3));
|
||||||
@@ -39,11 +40,11 @@ function obj = teardown(obj)
|
|||||||
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;
|
||||||
|
|||||||
@@ -61,13 +61,15 @@ function [obj] = updatePlots(obj)
|
|||||||
end
|
end
|
||||||
|
|
||||||
% Update h function plots
|
% Update h function plots
|
||||||
for ii = 1:size(obj.caPlot, 1)
|
nCA = size(obj.caPlot, 1);
|
||||||
obj.caPlot(ii).YData(obj.timestepIndex) = obj.h(ii, obj.timestepIndex);
|
nObs = size(obj.obsPlot, 1);
|
||||||
|
for ii = 1:nCA
|
||||||
|
obj.caPlot(ii).YData(obj.timestepIndex) = obj.barriers(ii, obj.timestepIndex);
|
||||||
end
|
end
|
||||||
for ii = 1:size(obj.obsPlot, 1)
|
for ii = 1:nObs
|
||||||
obj.obsPlot(ii).YData(obj.timestepIndex) = obj.h(ii + size(obj.caPlot, 1), obj.timestepIndex);
|
obj.obsPlot(ii).YData(obj.timestepIndex) = obj.barriers(nCA + ii, 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.h(ii + size(obj.caPlot, 1) + size(obj.obsPlot, 1), obj.timestepIndex);
|
obj.domPlot(ii).YData(obj.timestepIndex) = obj.barriers(nCA + nObs + ii, obj.timestepIndex);
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
+4
-5
@@ -7,11 +7,11 @@ function validate(obj)
|
|||||||
|
|
||||||
%% Communications Network Validators
|
%% Communications Network Validators
|
||||||
if max(conncomp(graph(obj.adjacency))) ~= 1
|
if max(conncomp(graph(obj.adjacency))) ~= 1
|
||||||
warning("Network is not connected");
|
error("Network is not connected");
|
||||||
end
|
end
|
||||||
|
|
||||||
if any(obj.adjacency - obj.constraintAdjacencyMatrix < 0, "all")
|
if any(obj.adjacency - obj.constraintAdjacencyMatrix < 0, "all")
|
||||||
warning("Eliminated network connections that were necessary");
|
error("Eliminated network connections that were necessary");
|
||||||
end
|
end
|
||||||
|
|
||||||
%% Obstacle Validators
|
%% Obstacle Validators
|
||||||
@@ -20,10 +20,9 @@ function validate(obj)
|
|||||||
for kk = 1:size(obj.agents, 1)
|
for kk = 1:size(obj.agents, 1)
|
||||||
P = min(max(obj.agents{kk}.pos, obj.obstacles{jj}.minCorner), obj.obstacles{jj}.maxCorner);
|
P = min(max(obj.agents{kk}.pos, obj.obstacles{jj}.minCorner), obj.obstacles{jj}.maxCorner);
|
||||||
d = obj.agents{kk}.pos - P;
|
d = obj.agents{kk}.pos - P;
|
||||||
if dot(d, d) < obj.agents{kk}.collisionGeometry.radius^2
|
if dot(d, d) < obj.agents{kk}.collisionGeometry.radius^2 - 1e-3
|
||||||
warning("%s colliding with %s by %d", obj.agents{kk}.label, obj.obstacles{jj}.label, dot(d, d) - obj.agents{kk}.collisionGeometry.radius^2); % this will cause quadprog to fail
|
error("%s colliding with %s by %d", obj.agents{kk}.label, obj.obstacles{jj}.label, - dot(d, d) + obj.agents{kk}.collisionGeometry.radius^2); % this will cause quadprog to fail
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
end
|
end
|
||||||
|
|||||||
+16
-5
@@ -5,26 +5,37 @@ 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.alphaDist, obj.agents);
|
betaTilt = cellfun(@(x) x.sensorModel.betaTilt, 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, "minAlt", obj.obstacles{end}.maxCorner(3), ...
|
inits = struct("timestep", obj.timestep, "maxIter", obj.maxIter + 1, "minAlt", obj.minAlt, ...
|
||||||
"discretizationStep", obj.domain.objective.discretizationStep, "protectedRange", obj.domain.objective.protectedRange, ...
|
"discretizationStep", obj.domain.objective.discretizationStep, "protectedRange", obj.domain.objective.protectedRange, ...
|
||||||
"sensorPerformanceMinimum", obj.domain.objective.sensorPerformanceMinimum, "initialStepSize", initialStepSize, ...
|
"sensorPerformanceMinimum", obj.domain.objective.sensorPerformanceMinimum, "initialStepSize", initialStepSize, ...
|
||||||
"barrierGain", obj.barrierGain, "barrierExponent", obj.barrierExponent, "numObstacles", size(obj.obstacles, 1), ...
|
"barrierGain", obj.barrierGain, "barrierExponent", obj.barrierExponent, "numObstacles", numInputObs, ...
|
||||||
"numAgents", size(obj.agents, 1), "collisionRadius", collisionRadii, "comRange", comRanges, ...
|
"numAgents", size(obj.agents, 1), "collisionRadius", collisionRadii, "comRange", comRanges, ...
|
||||||
"useDoubleIntegrator", obj.useDoubleIntegrator, "dampingCoeff", obj.dampingCoeff, ...
|
"useDoubleIntegrator", obj.useDoubleIntegrator, "dampingCoeff", obj.dampingCoeff, "useFixedTopology", obj.useFixedTopology, ...
|
||||||
"alphaDist", alphaDist, "betaDist", betaDist, "alphaTilt", alphaTilt, "betaTilt", betaTilt, ...
|
"alphaDist", alphaDist, "betaDist", betaDist, "alphaTilt", alphaTilt, "betaTilt", betaTilt, ...
|
||||||
... % ^^^ PARAMETERS ^^^ | vvv STATES vvv
|
... % ^^^ PARAMETERS ^^^ | vvv STATES vvv
|
||||||
"pos", pos); % still needs obstacle states and objective state
|
"pos", pos, "objectivePos", obj.domain.objective.groundPos, "objectiveSigma", obj.domain.objective.objectiveSigma, ...
|
||||||
|
"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");
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
function obj = initialize(obj, objectiveFunction, domain, discretizationStep, protectedRange, sensorPerformanceMinimum)
|
function obj = initialize(obj, objectiveFunction, domain, discretizationStep, protectedRange, sensorPerformanceMinimum, objectiveMu, objectiveSigma)
|
||||||
arguments (Input)
|
arguments (Input)
|
||||||
obj (1,1) {mustBeA(obj, "sensingObjective")};
|
obj (1,1) {mustBeA(obj, "sensingObjective")};
|
||||||
objectiveFunction (1, 1) {mustBeA(objectiveFunction, "function_handle")};
|
objectiveFunction (1, 1) {mustBeA(objectiveFunction, "function_handle")};
|
||||||
@@ -6,6 +6,8 @@ function obj = initialize(obj, objectiveFunction, domain, discretizationStep, pr
|
|||||||
discretizationStep (1, 1) double = 1;
|
discretizationStep (1, 1) double = 1;
|
||||||
protectedRange (1, 1) double = 1;
|
protectedRange (1, 1) double = 1;
|
||||||
sensorPerformanceMinimum (1, 1) double = 1e-6;
|
sensorPerformanceMinimum (1, 1) double = 1e-6;
|
||||||
|
objectiveMu (:, 2) double = NaN(1, 2);
|
||||||
|
objectiveSigma (:, 2, 2) double = NaN(1, 2, 2);
|
||||||
end
|
end
|
||||||
arguments (Output)
|
arguments (Output)
|
||||||
obj (1,1) {mustBeA(obj, "sensingObjective")};
|
obj (1,1) {mustBeA(obj, "sensingObjective")};
|
||||||
@@ -37,8 +39,13 @@ function obj = initialize(obj, objectiveFunction, domain, discretizationStep, pr
|
|||||||
|
|
||||||
% store ground position
|
% store ground position
|
||||||
idx = obj.values == 1;
|
idx = obj.values == 1;
|
||||||
|
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, domain.center(3)]) > protectedRange, "Domain is crowding the sensing objective")
|
assert(domain.distance([obj.groundPos, ones(size(obj.groundPos, 1), 1) .* domain.center(3)]) > protectedRange, "Domain is crowding the sensing objective");
|
||||||
end
|
end
|
||||||
@@ -11,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
|
while domain.distance(mu) < protectedRange * 1.01
|
||||||
mu = domain.random();
|
mu = domain.random();
|
||||||
end
|
end
|
||||||
|
|
||||||
% Set random distribution parameters
|
% Set random distribution parameters
|
||||||
sig = [2 + rand * 2, 1; 1, 2 + rand * 2];
|
sig = reshape([2 + rand * 2, 1; 1, 2 + rand * 2], [1 2 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);
|
obj = obj.initialize(objectiveFunction, domain, discretizationStep, protectedRange, 1e-6, mu(1:2), sig);
|
||||||
end
|
end
|
||||||
@@ -2,7 +2,8 @@ classdef sensingObjective
|
|||||||
% Sensing objective definition parent class
|
% Sensing objective definition parent class
|
||||||
properties (SetAccess = private, GetAccess = public)
|
properties (SetAccess = private, GetAccess = public)
|
||||||
label = "";
|
label = "";
|
||||||
groundPos = [NaN, NaN];
|
groundPos = NaN(1, 2);
|
||||||
|
objectiveSigma = NaN(1, 2, 2);
|
||||||
discretizationStep = NaN;
|
discretizationStep = NaN;
|
||||||
X = [];
|
X = [];
|
||||||
Y = [];
|
Y = [];
|
||||||
|
|||||||
@@ -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(10):
|
for attempt in range(100):
|
||||||
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),
|
||||||
|
|||||||
@@ -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.109.1 from E-VM perspective)
|
# Controller runs on host machine (192.168.X.1, generally)
|
||||||
controller:
|
controller:
|
||||||
ip: "192.168.109.1"
|
ip: "192.168.112.1"
|
||||||
port: 5000
|
port: 5000
|
||||||
|
|||||||
@@ -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.109.1 from E-VM perspective)
|
# Controller runs on host machine (192.168.X.1, generally)
|
||||||
controller:
|
controller:
|
||||||
ip: "192.168.109.1"
|
ip: "192.168.112.1"
|
||||||
port: 5000
|
port: 5000
|
||||||
@@ -1,2 +1,2 @@
|
|||||||
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax, 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, useDoubleIntegrator, dampingCoeff, useFixedTopology
|
||||||
5, 100, 30.0, 0.1, 2.0, 2.0, 100, 3, "5.0, 5.0", "25.0, 25.0", "80.0, 80.0", "0.25, 0.25", "5.0, 5.0", "0.1, 0.1", "0.0, 0.0, 0.0", "80.0, 80.0, 80.0", "55.0, 55.0", "40, 25, 25, 40", 0.15, "15.0, 10.0, 40.0, 5.0, 10.0, 45.0", 1, "1.0, 25.0, 0.0", "30.0, 30.0, 50.0", 1, 2.0, 1
|
1, 50, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 50.0", "0.25, 1.0", "8.0, 25.0", "0.1, 0.02", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "60.0, 80.0, 45.0, 70.0", "70, 15, 15, 20, 20, 15, 15, 70", 0.15, "10.0, 10.0, 50.0, 40.0, 15.0, 45.0", 8, "0.0, 30.0, 0.0, 42.0, 30.0, 0.0, 84.0, 30.0, 0.0, 13.0, 60.0, 0.0, 55.0, 60.0, 0.0, 0.0, 90, 0.0, 42.0, 90.0, 0.0, 84.0, 90.0, 0.0", "16.0, 40.0, 100.0, 58.0, 40.0, 100.0, 100.0, 40.0, 100.0, 29.0, 70.0, 100.0, 71.0, 70.0, 100.0, 16.0, 100.0, 100.0, 58.0, 100.0, 100.0, 100.0, 100.0, 100.0", 0, 2.0, 1
|
||||||
|
@@ -0,0 +1,2 @@
|
|||||||
|
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax, useDoubleIntegrator, dampingCoeff, useFixedTopology
|
||||||
|
1, 80, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 50.0", "0.25, 1.0", "8.0, 25.0", "0.1, 0.02", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "60.0, 80.0, 45.0, 70.0", "70, 15, 15, 20, 20, 15, 15, 70", 0.15, "15.0, 15.0, 50.0, 40.0, 10.0, 45.0", 8, "0.0, 30.0, 0.0, 42.0, 30.0, 0.0, 84.0, 30.0, 0.0, 13.0, 60.0, 0.0, 55.0, 60.0, 0.0, 0.0, 90, 0.0, 42.0, 90.0, 0.0, 84.0, 90.0, 0.0", "16.0, 40.0, 100.0, 58.0, 40.0, 100.0, 100.0, 40.0, 100.0, 29.0, 70.0, 100.0, 71.0, 70.0, 100.0, 16.0, 100.0, 100.0, 58.0, 100.0, 100.0, 100.0, 100.0, 100.0", 0, 2.0, 1
|
||||||
|
@@ -0,0 +1,2 @@
|
|||||||
|
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax, useDoubleIntegrator, dampingCoeff, useFixedTopology
|
||||||
|
1, 125, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 50.0", "0.25, 1.0", "8.0, 25.0", "0.1, 0.02", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "30.0, 80.0", "60, 20, 20, 30", 0.15, "65.0, 15.0, 65.0, 65.0, 15.0, 45.0", 3, "0.0, 25.0, 55.0, 40.0, 10.0, 0.0, 40.0, 45.0, 60.0", "100.0, 70.0, 60.0, 45.0, 80.0, 55.0, 100.0, 50.0, 100.0", 0, 2.0, 1
|
||||||
|
@@ -0,0 +1,2 @@
|
|||||||
|
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax, useDoubleIntegrator, dampingCoeff, useFixedTopology
|
||||||
|
1, 100, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 80.0", "0.25, 0.25", "8.0, 8.0", "0.1, 0.1", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "66.6, 66.6", "55, 35, 35, 55", 0.15, "15.0, 15.0, 50.0, 40.0, 15.0, 50.0", 1, "0.0, 35.0, 0.0", "50, 40.0, 60", 1, 2.0, 1
|
||||||
|
@@ -0,0 +1,2 @@
|
|||||||
|
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax, useDoubleIntegrator, dampingCoeff, useFixedTopology
|
||||||
|
1, 125, 35.0, 0.1, 2.0, 6, 1, 1, "8.0, 8.0", "35.0, 35.0", "80.0, 50.0", "0.25, 1.0", "8.0, 25.0", "0.1, 0.02", "0.0, 0.0, 0.0", "100.0, 100.0, 100.0", "30.0, 80.0", "60, 20, 20, 30", 0.15, "90.0, 10.0, 50.0, 65.0, 15.0, 45.0", 4, "0.0, 30.0, 0.0, 70.0, 30.0, 0.0, 0.0, 60.0, 0.0, 55.0, 60.0, 0.0", "50.0, 40.0, 100.0, 100.0, 40.0, 100.0, 35.0, 70.0, 100.0, 100.0, 70.0, 100.0", 0, 2.0, 1
|
||||||
|
+209
-120
@@ -138,6 +138,41 @@
|
|||||||
<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="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 id="32" type="coderapp.internal.codertype.PrimitiveType">
|
||||||
|
<ClassName>int32</ClassName>
|
||||||
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
|
</Types>
|
||||||
|
<Types id="33" type="coderapp.internal.codertype.PrimitiveType">
|
||||||
|
<ClassName>int32</ClassName>
|
||||||
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
|
</Types>
|
||||||
|
<Types id="34" 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>
|
||||||
@@ -379,719 +414,773 @@
|
|||||||
</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.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/cone.cpp</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/controller.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="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.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/constrainMotion.cpp</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_data.cpp</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/constrainMotion.h</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.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="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_initialize.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="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.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="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_internal_types.h</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="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_terminate.cpp</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="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.h</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="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_types.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="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/countsort.cpp</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="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.h</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="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/deleteColMoveEnd.cpp</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="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.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="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/dot.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="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.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="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/driver.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="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.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="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/exp.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="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.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="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/eye.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="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.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="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/factorQR.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="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.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="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/feasibleX0ForWorkingSet.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="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.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="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/feasibleratiotest.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="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.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="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/find.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="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.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="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/fullColLDL2_.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="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_.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="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/guidance_step.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="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.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="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/iterate.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="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.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="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/ixamax.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="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.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="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/ixfun.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="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.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="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/lesserNeighbor.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="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.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="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/linearForm_.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="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_.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="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/maxConstraintViolation.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="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.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="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/meshgrid.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="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.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="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/miSim.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="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.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="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/minOrMax.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="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.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="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/mpower.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="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.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="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/nchoosek.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="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.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="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/norm.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="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.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="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/partition.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="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.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="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/phaseone.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="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.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="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/quadprog.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="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.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="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/ratiotest.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="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.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="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/rectangularPrism.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/quadprog.h</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="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/removeConstr.cpp</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ratiotest.cpp</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="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/removeConstr.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/ratiotest.h</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="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/repmat.cpp</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/rectangularPrism.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/repmat.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="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/rtGetInf.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="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/rtGetInf.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="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/rtGetNaN.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="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/rtGetNaN.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="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/rt_defines.h</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="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/rt_nonfinite.cpp</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="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_nonfinite.h</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="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/rtwtypes.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="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/run.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="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/run.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="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/sensingObjective.cpp</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="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/sensingObjective.h</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="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/sensorPerformance.cpp</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="125" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="125" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sensorPerformance.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="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/setProblemType.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="127" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="127" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/setProblemType.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="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/sigmoidSensor.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sensorPerformance.cpp</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="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/sort.cpp</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sensorPerformance.h</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="130" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="130" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sort.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/setProblemType.cpp</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="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/spherical.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="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/sprintf.cpp</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sigmoidSensor.cpp</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="133" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="133" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sprintf.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sigmoidSensor.h</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="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/squareQ_appendCol.cpp</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="135" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="135" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/squareQ_appendCol.h</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="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/string1.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/spherical.cpp</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/sum.cpp</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="138" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="138" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sum.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sprintf.cpp</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="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/unique.cpp</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/sprintf.h</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="140" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="140" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/unique.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/squareQ_appendCol.cpp</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="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/vecnorm.cpp</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/squareQ_appendCol.h</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="142" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="142" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/vecnorm.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/string1.cpp</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/xgemv.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="144" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="144" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xgemv.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="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/xgeqp3.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="146" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="146" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xgeqp3.h</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/triu.cpp</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/xnrm2.cpp</Path>
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/triu.h</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="148" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="148" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xnrm2.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="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/xrotg.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="150" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="150" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xrotg.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="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/xzgeqp3.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="152" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="152" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzgeqp3.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="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/xzlarf.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="154" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="154" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarf.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="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/xzlarfg.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="156" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="156" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
<File type="coderapp.internal.util.mfz.FileSpec">
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xzlarfg.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="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/matlab/R2025a/extern/include/tmwtypes.h</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="158" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="158" 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/xrotg.cpp</Path>
|
||||||
</File>
|
</File>
|
||||||
<Type>GENERATED_SOURCE</Type>
|
<Type>GENERATED_SOURCE</Type>
|
||||||
</Artifacts>
|
</Artifacts>
|
||||||
<Artifacts id="159" type="coderapp.internal.build.mfz.CodegenArtifact">
|
<Artifacts id="159" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/xrotg.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/xzgeqp3.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/xzgeqp3.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/xzlarf.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/xzlarf.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/Desktop/miSim/aerpaw/codegen/xzlarfg.cpp</Path>
|
||||||
|
</File>
|
||||||
|
<Type>GENERATED_SOURCE</Type>
|
||||||
|
</Artifacts>
|
||||||
|
<Artifacts id="165" 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="166" 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="167" type="coderapp.internal.build.mfz.CodegenArtifact">
|
||||||
|
<File type="coderapp.internal.util.mfz.FileSpec">
|
||||||
|
<Path>/home/kdee/Desktop/miSim/aerpaw/codegen/examples/main.cpp</Path>
|
||||||
|
</File>
|
||||||
|
<Type>GENERATED_SOURCE</Type>
|
||||||
|
</Artifacts>
|
||||||
|
<Artifacts id="168" 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>
|
||||||
@@ -1099,7 +1188,7 @@
|
|||||||
</Artifacts>
|
</Artifacts>
|
||||||
<BuildFolder type="coderapp.internal.util.mfz.FileSpec"/>
|
<BuildFolder type="coderapp.internal.util.mfz.FileSpec"/>
|
||||||
<Success>true</Success>
|
<Success>true</Success>
|
||||||
<Timestamp>2026-03-11T17:11:03</Timestamp>
|
<Timestamp>2026-04-07T22:43:01</Timestamp>
|
||||||
</MainBuildResult>
|
</MainBuildResult>
|
||||||
</coderapp.internal.mlc.mfz.MatlabCoderProjectState>
|
</coderapp.internal.mlc.mfz.MatlabCoderProjectState>
|
||||||
</MF0>
|
</MF0>
|
||||||
|
|||||||
+118
-11
@@ -7,34 +7,47 @@ 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;
|
||||||
MAX_TARGETS = MAX_CLIENTS;
|
% Three waypoints per UAV: one axis-aligned move per dimension (taxicab flyout/flyback)
|
||||||
|
MAX_TARGETS = MAX_CLIENTS * 3;
|
||||||
|
|
||||||
|
% Taxicab flyout/flyback only supports exactly 2 UAVs
|
||||||
|
if numClients ~= int32(2)
|
||||||
|
error('Taxicab flyout/flyback requires exactly 2 UAVs');
|
||||||
|
end
|
||||||
|
|
||||||
% Allocate targets array (MAX_TARGETS x 3)
|
% Allocate targets array (MAX_TARGETS x 3)
|
||||||
targets = zeros(MAX_TARGETS, 3);
|
targets = zeros(MAX_TARGETS, 3);
|
||||||
numWaypoints = int32(0);
|
numWaypoints = int32(0);
|
||||||
totalLoaded = int32(0); % pre-declare type for coder.ceval %#ok<NASGU>
|
totalLoaded = int32(0); % pre-declare type for coder.ceval %#ok<NASGU>
|
||||||
|
|
||||||
% Load initial UAV positions from scenario CSV
|
% Experiment start positions from scenario CSV (N x 3)
|
||||||
|
scenarioPositions = zeros(MAX_CLIENTS, 3);
|
||||||
|
|
||||||
|
% Load experiment start positions from scenario CSV
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
disp('Loading initial positions from scenario.csv (simulation)...');
|
disp('Loading initial positions from scenario.csv (simulation)...');
|
||||||
tmpSim = miSim;
|
tmpSim = miSim;
|
||||||
sc = tmpSim.readScenarioCsv('aerpaw/config/scenario.csv');
|
sc = tmpSim.readScenarioCsv('aerpaw/config/scenario.csv');
|
||||||
flatPos = double(sc.initialPositions); % 1×(3*N) flat vector
|
flatPos = double(sc.initialPositions); % 1×(3*N) flat vector
|
||||||
posMatrix = reshape(flatPos, 3, [])'; % N×3, same layout as initializeFromCsv
|
posMatrix = reshape(flatPos, 3, [])'; % N×3
|
||||||
totalLoaded = int32(size(posMatrix, 1));
|
totalLoaded = int32(size(posMatrix, 1));
|
||||||
|
scenarioPositions(1:totalLoaded, :) = posMatrix;
|
||||||
|
% MATLAB path: send directly to scenario positions in one waypoint
|
||||||
targets(1:totalLoaded, :) = posMatrix;
|
targets(1:totalLoaded, :) = posMatrix;
|
||||||
numWaypoints = int32(1);
|
numWaypoints = int32(1);
|
||||||
disp(['Loaded ', num2str(double(totalLoaded)), ' initial positions']);
|
disp(['Loaded ', num2str(double(totalLoaded)), ' initial positions']);
|
||||||
else
|
else
|
||||||
coder.cinclude('controller_impl.h');
|
coder.cinclude('controller_impl.h');
|
||||||
filename = ['config/scenario.csv', char(0)];
|
filename = ['config/scenario.csv', char(0)];
|
||||||
|
% Load into targets temporarily; copy to scenarioPositions below
|
||||||
totalLoaded = coder.ceval('loadInitialPositions', coder.ref(filename), ...
|
totalLoaded = coder.ceval('loadInitialPositions', coder.ref(filename), ...
|
||||||
coder.ref(targets), int32(MAX_TARGETS));
|
coder.ref(targets), int32(MAX_TARGETS));
|
||||||
numWaypoints = totalLoaded / int32(numClients);
|
scenarioPositions(1:totalLoaded, :) = targets(1:totalLoaded, :);
|
||||||
|
numWaypoints = int32(3);
|
||||||
end
|
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 = 48;
|
||||||
MAX_OBSTACLES_CTRL = int32(8);
|
MAX_OBSTACLES_CTRL = int32(8);
|
||||||
scenarioParams = zeros(1, NUM_SCENARIO_PARAMS);
|
scenarioParams = zeros(1, NUM_SCENARIO_PARAMS);
|
||||||
obstacleMin = zeros(MAX_OBSTACLES_CTRL, 3);
|
obstacleMin = zeros(MAX_OBSTACLES_CTRL, 3);
|
||||||
@@ -68,6 +81,46 @@ for i = 1:numClients
|
|||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
% Query takeoff-pad GPS positions before sending any waypoints.
|
||||||
|
% These are also the flyback targets so each UAV lands where it took off.
|
||||||
|
initialPositions = zeros(MAX_CLIENTS, 3);
|
||||||
|
if ~coder.target('MATLAB')
|
||||||
|
coder.ceval('sendRequestPositions', int32(numClients));
|
||||||
|
coder.ceval('recvPositions', int32(numClients), coder.ref(initialPositions), int32(MAX_CLIENTS));
|
||||||
|
else
|
||||||
|
% Simulation: treat scenario positions as the takeoff locations
|
||||||
|
initialPositions(1:totalLoaded, :) = scenarioPositions(1:totalLoaded, :);
|
||||||
|
end
|
||||||
|
|
||||||
|
% ---- Build taxicab flyout waypoints ------------------------------------------
|
||||||
|
% Determine which UAV has the higher final altitude; it moves Z first so it
|
||||||
|
% clears vertical separation before the lower UAV converges on the same X/Y.
|
||||||
|
% Higher UAV order: Z → Y → X
|
||||||
|
% Lower UAV order: X → Y → Z
|
||||||
|
if ~coder.target('MATLAB')
|
||||||
|
if scenarioPositions(1, 3) >= scenarioPositions(2, 3)
|
||||||
|
higherIdx = int32(1);
|
||||||
|
lowerIdx = int32(2);
|
||||||
|
else
|
||||||
|
higherIdx = int32(2);
|
||||||
|
lowerIdx = int32(1);
|
||||||
|
end
|
||||||
|
|
||||||
|
hBase = double(higherIdx - 1) * double(numWaypoints);
|
||||||
|
lBase = double(lowerIdx - 1) * double(numWaypoints);
|
||||||
|
|
||||||
|
% Higher UAV: Z first
|
||||||
|
targets(hBase + 1, :) = [initialPositions(higherIdx,1), initialPositions(higherIdx,2), scenarioPositions(higherIdx,3)];
|
||||||
|
targets(hBase + 2, :) = [initialPositions(higherIdx,1), scenarioPositions(higherIdx,2), scenarioPositions(higherIdx,3)];
|
||||||
|
targets(hBase + 3, :) = scenarioPositions(higherIdx, :);
|
||||||
|
|
||||||
|
% Lower UAV: X first
|
||||||
|
targets(lBase + 1, :) = [scenarioPositions(lowerIdx,1), initialPositions(lowerIdx,2), initialPositions(lowerIdx,3)];
|
||||||
|
targets(lBase + 2, :) = [scenarioPositions(lowerIdx,1), scenarioPositions(lowerIdx,2), initialPositions(lowerIdx,3)];
|
||||||
|
targets(lBase + 3, :) = scenarioPositions(lowerIdx, :);
|
||||||
|
end
|
||||||
|
% ------------------------------------------------------------------------------
|
||||||
|
|
||||||
% Waypoint loop: send each waypoint to all clients, wait for all to arrive
|
% Waypoint loop: send each waypoint to all clients, wait for all to arrive
|
||||||
for w = 1:numWaypoints
|
for w = 1:numWaypoints
|
||||||
% Send TARGET for waypoint w to each client
|
% Send TARGET for waypoint w to each client
|
||||||
@@ -78,7 +131,7 @@ for w = 1:numWaypoints
|
|||||||
target = targets(targetIdx, :);
|
target = targets(targetIdx, :);
|
||||||
|
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
disp([datestr(now, 'HH:MM:SS'), ' Sending TARGET to client ', num2str(i), ' (waypoint ', num2str(w), '): ', ...
|
disp(['Sending TARGET to client ', num2str(i), ' (waypoint ', num2str(w), '): ', ...
|
||||||
num2str(target(1)), ',', num2str(target(2)), ',', num2str(target(3))]);
|
num2str(target(1)), ',', num2str(target(2)), ',', num2str(target(3))]);
|
||||||
else
|
else
|
||||||
coder.ceval('sendTarget', int32(i), coder.ref(target));
|
coder.ceval('sendTarget', int32(i), coder.ref(target));
|
||||||
@@ -103,8 +156,13 @@ for w = 1:numWaypoints
|
|||||||
end
|
end
|
||||||
|
|
||||||
% ---- Phase 2: miSim guidance loop ----------------------------------------
|
% ---- Phase 2: miSim guidance loop ----------------------------------------
|
||||||
% Guidance parameters (adjust here and recompile as needed)
|
% Number of guidance steps comes from maxIter in scenario.csv (scenarioParams(2))
|
||||||
MAX_GUIDANCE_STEPS = int32(100); % number of guidance iterations
|
% so the controller and the agent step-decay schedule stay in sync.
|
||||||
|
if coder.target('MATLAB')
|
||||||
|
MAX_GUIDANCE_STEPS = int32(sc.maxIter);
|
||||||
|
else
|
||||||
|
MAX_GUIDANCE_STEPS = int32(scenarioParams(2));
|
||||||
|
end
|
||||||
|
|
||||||
% Enter guidance mode on all clients
|
% Enter guidance mode on all clients
|
||||||
if ~coder.target('MATLAB')
|
if ~coder.target('MATLAB')
|
||||||
@@ -117,14 +175,18 @@ if ~coder.target('MATLAB')
|
|||||||
coder.ceval('sendRequestPositions', int32(numClients));
|
coder.ceval('sendRequestPositions', int32(numClients));
|
||||||
coder.ceval('recvPositions', int32(numClients), coder.ref(positions), int32(MAX_CLIENTS));
|
coder.ceval('recvPositions', int32(numClients), coder.ref(positions), int32(MAX_CLIENTS));
|
||||||
else
|
else
|
||||||
% Simulation: seed positions from CSV waypoints so agents don't start at origin
|
% Simulation: seed positions from scenario positions so agents don't start at origin
|
||||||
positions(1:totalLoaded, :) = targets(1:totalLoaded, :);
|
positions(1:totalLoaded, :) = scenarioPositions(1:totalLoaded, :);
|
||||||
end
|
end
|
||||||
guidance_step(positions(1:numClients, :), true, ...
|
guidance_step(positions(1:numClients, :), true, ...
|
||||||
scenarioParams, obstacleMin, obstacleMax, numObstacles);
|
scenarioParams, obstacleMin, obstacleMax, numObstacles);
|
||||||
|
|
||||||
% Main guidance loop (event-triggered)
|
% Main guidance loop (event-triggered)
|
||||||
for step = 1:MAX_GUIDANCE_STEPS
|
for step = 1:MAX_GUIDANCE_STEPS
|
||||||
|
if ~coder.target('MATLAB')
|
||||||
|
coder.ceval('setGuidanceStep', int32(step), int32(MAX_GUIDANCE_STEPS));
|
||||||
|
end
|
||||||
|
|
||||||
% Run one guidance step: feed current GPS positions in, get targets out
|
% Run one guidance step: feed current GPS positions in, get targets out
|
||||||
nextPositions = guidance_step(positions(1:numClients, :), false, ...
|
nextPositions = guidance_step(positions(1:numClients, :), false, ...
|
||||||
scenarioParams, obstacleMin, obstacleMax, numObstacles);
|
scenarioParams, obstacleMin, obstacleMax, numObstacles);
|
||||||
@@ -135,7 +197,7 @@ for step = 1:MAX_GUIDANCE_STEPS
|
|||||||
if ~coder.target('MATLAB')
|
if ~coder.target('MATLAB')
|
||||||
coder.ceval('sendTarget', int32(i), coder.ref(target));
|
coder.ceval('sendTarget', int32(i), coder.ref(target));
|
||||||
else
|
else
|
||||||
disp([datestr(now, 'HH:MM:SS'), ' [guidance] target UAV ', num2str(i), ': ', num2str(target)]);
|
disp(['[step ', num2str(step), '] target UAV ', num2str(i), ': ', num2str(target)]);
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
@@ -164,6 +226,51 @@ if ~coder.target('MATLAB')
|
|||||||
% last guidance navigation and is back in sequential (ACK/READY) mode.
|
% last guidance navigation and is back in sequential (ACK/READY) mode.
|
||||||
coder.ceval('waitForAllMessageType', int32(numClients), ...
|
coder.ceval('waitForAllMessageType', int32(numClients), ...
|
||||||
int32(MESSAGE_TYPE.ACK));
|
int32(MESSAGE_TYPE.ACK));
|
||||||
|
% Reset step counter so post-guidance logging carries no step prefix.
|
||||||
|
coder.ceval('setGuidanceStep', int32(0), int32(MAX_GUIDANCE_STEPS));
|
||||||
|
end
|
||||||
|
% --------------------------------------------------------------------------
|
||||||
|
|
||||||
|
% ---- Taxicab flyback: return each UAV to its takeoff-pad position ---------
|
||||||
|
% The UAV that ended guidance at the higher altitude moves Z last (X → Y → Z)
|
||||||
|
% so it stays high while the lower UAV descends first, maintaining separation
|
||||||
|
% as both converge back on their respective home X/Y positions.
|
||||||
|
NUM_RETURN_WP = int32(3);
|
||||||
|
returnTargets = zeros(MAX_TARGETS, 3);
|
||||||
|
|
||||||
|
if ~coder.target('MATLAB')
|
||||||
|
if positions(1, 3) >= positions(2, 3)
|
||||||
|
higherRetIdx = int32(1);
|
||||||
|
lowerRetIdx = int32(2);
|
||||||
|
else
|
||||||
|
higherRetIdx = int32(2);
|
||||||
|
lowerRetIdx = int32(1);
|
||||||
|
end
|
||||||
|
|
||||||
|
hRetBase = double(higherRetIdx - 1) * double(NUM_RETURN_WP);
|
||||||
|
lRetBase = double(lowerRetIdx - 1) * double(NUM_RETURN_WP);
|
||||||
|
|
||||||
|
% Higher post-guidance UAV: X → Y → Z (descend last)
|
||||||
|
returnTargets(hRetBase + 1, :) = [initialPositions(higherRetIdx,1), positions(higherRetIdx,2), positions(higherRetIdx,3)];
|
||||||
|
returnTargets(hRetBase + 2, :) = [initialPositions(higherRetIdx,1), initialPositions(higherRetIdx,2), positions(higherRetIdx,3)];
|
||||||
|
returnTargets(hRetBase + 3, :) = initialPositions(higherRetIdx, :);
|
||||||
|
|
||||||
|
% Lower post-guidance UAV: Z → Y → X (descend first)
|
||||||
|
returnTargets(lRetBase + 1, :) = [positions(lowerRetIdx,1), positions(lowerRetIdx,2), initialPositions(lowerRetIdx,3)];
|
||||||
|
returnTargets(lRetBase + 2, :) = [positions(lowerRetIdx,1), initialPositions(lowerRetIdx,2), initialPositions(lowerRetIdx,3)];
|
||||||
|
returnTargets(lRetBase + 3, :) = initialPositions(lowerRetIdx, :);
|
||||||
|
|
||||||
|
for w = 1:NUM_RETURN_WP
|
||||||
|
for i = 1:numClients
|
||||||
|
retIdx = double(i - 1) * double(NUM_RETURN_WP) + w;
|
||||||
|
retTarget = returnTargets(retIdx, :);
|
||||||
|
coder.ceval('sendTarget', int32(i), coder.ref(retTarget));
|
||||||
|
end
|
||||||
|
coder.ceval('waitForAllMessageType', int32(numClients), int32(MESSAGE_TYPE.ACK));
|
||||||
|
coder.ceval('waitForAllMessageType', int32(numClients), int32(MESSAGE_TYPE.READY));
|
||||||
|
end
|
||||||
|
else
|
||||||
|
disp('Taxicab return (simulation): UAVs commanded back to takeoff positions.');
|
||||||
end
|
end
|
||||||
% --------------------------------------------------------------------------
|
% --------------------------------------------------------------------------
|
||||||
|
|
||||||
|
|||||||
+12
-2
@@ -29,6 +29,9 @@ function nextPositions = guidance_step(currentPositions, isInit, ...
|
|||||||
% 39-40 objectivePos
|
% 39-40 objectivePos
|
||||||
% 41-44 objectiveVar (2x2, col-major)
|
% 41-44 objectiveVar (2x2, col-major)
|
||||||
% 45 sensorPerformanceMinimum
|
% 45 sensorPerformanceMinimum
|
||||||
|
% 46 useDoubleIntegrator
|
||||||
|
% 47 dampingCoeff
|
||||||
|
% 48 useFixedTopology
|
||||||
% obstacleMin (MAX_OBSTACLES × 3) double column-major obstacle corners (compiled path)
|
% obstacleMin (MAX_OBSTACLES × 3) double column-major obstacle corners (compiled path)
|
||||||
% obstacleMax (MAX_OBSTACLES × 3) double
|
% obstacleMax (MAX_OBSTACLES × 3) double
|
||||||
% numObstacles (1,1) int32 actual obstacle count
|
% numObstacles (1,1) int32 actual obstacle count
|
||||||
@@ -94,6 +97,9 @@ if isInit
|
|||||||
OBJECTIVE_GROUND_POS = scenarioParams(39:40);
|
OBJECTIVE_GROUND_POS = scenarioParams(39:40);
|
||||||
OBJECTIVE_VAR = reshape(scenarioParams(41:44), 2, 2);
|
OBJECTIVE_VAR = reshape(scenarioParams(41:44), 2, 2);
|
||||||
SENSOR_PERFORMANCE_MINIMUM = scenarioParams(45);
|
SENSOR_PERFORMANCE_MINIMUM = scenarioParams(45);
|
||||||
|
USE_DOUBLE_INTEGRATOR = logical(scenarioParams(46));
|
||||||
|
DAMPING_COEFF = scenarioParams(47);
|
||||||
|
USE_FIXED_TOPOLOGY = logical(scenarioParams(48));
|
||||||
|
|
||||||
% --- Build domain geometry ---
|
% --- Build domain geometry ---
|
||||||
dom = rectangularPrism;
|
dom = rectangularPrism;
|
||||||
@@ -146,7 +152,8 @@ if isInit
|
|||||||
% --- Initialise simulation (plots and video disabled) ---
|
% --- Initialise simulation (plots and video disabled) ---
|
||||||
sim = miSim;
|
sim = miSim;
|
||||||
sim = sim.initialize(dom, agentList, BARRIER_GAIN, BARRIER_EXPONENT, ...
|
sim = sim.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
|
||||||
|
|
||||||
% On the init call return current positions unchanged
|
% On the init call return current positions unchanged
|
||||||
@@ -176,7 +183,9 @@ else
|
|||||||
sim.timestepIndex = sim.timestepIndex + 1;
|
sim.timestepIndex = sim.timestepIndex + 1;
|
||||||
|
|
||||||
% 3. Update communications topology (Lesser Neighbour Assignment)
|
% 3. Update communications topology (Lesser Neighbour Assignment)
|
||||||
|
if ~sim.useFixedTopology
|
||||||
sim = sim.lesserNeighbor();
|
sim = sim.lesserNeighbor();
|
||||||
|
end
|
||||||
|
|
||||||
% 4. Compute Voronoi partitioning
|
% 4. Compute Voronoi partitioning
|
||||||
sim.partitioning = sim.agents{1}.partition(sim.agents, sim.domain.objective);
|
sim.partitioning = sim.agents{1}.partition(sim.agents, sim.domain.objective);
|
||||||
@@ -184,7 +193,8 @@ else
|
|||||||
% 5. Unconstrained gradient-ascent step for each agent
|
% 5. Unconstrained gradient-ascent step for each agent
|
||||||
for ii = 1:size(sim.agents, 1)
|
for ii = 1:size(sim.agents, 1)
|
||||||
sim.agents{ii} = sim.agents{ii}.run(sim.domain, sim.partitioning, ...
|
sim.agents{ii} = sim.agents{ii}.run(sim.domain, sim.partitioning, ...
|
||||||
sim.timestepIndex, ii, sim.agents);
|
sim.timestepIndex, ii, sim.agents, ...
|
||||||
|
sim.useDoubleIntegrator, sim.dampingCoeff, sim.timestep);
|
||||||
end
|
end
|
||||||
|
|
||||||
% 6. Apply CBF safety filter (collision / comms / domain constraints via QP)
|
% 6. Apply CBF safety filter (collision / comms / domain constraints via QP)
|
||||||
|
|||||||
@@ -16,6 +16,44 @@
|
|||||||
|
|
||||||
static int serverSocket = -1;
|
static int serverSocket = -1;
|
||||||
static std::vector<int> clientSockets;
|
static std::vector<int> clientSockets;
|
||||||
|
static int guidanceStep = 0;
|
||||||
|
static int guidanceTotalSteps = 0;
|
||||||
|
static struct timespec lastStepTime = {0, 0};
|
||||||
|
|
||||||
|
// During guidance returns "(%d/%d) "; outside guidance returns "HH:MM:SS ".
|
||||||
|
static std::string logPrefix() {
|
||||||
|
if (guidanceStep > 0) {
|
||||||
|
char buf[32];
|
||||||
|
snprintf(buf, sizeof(buf), "(%d/%d) ", guidanceStep, guidanceTotalSteps);
|
||||||
|
return std::string(buf);
|
||||||
|
}
|
||||||
|
time_t now = time(nullptr);
|
||||||
|
struct tm* lt = localtime(&now);
|
||||||
|
char ts[16];
|
||||||
|
strftime(ts, sizeof(ts), "%H:%M:%S", lt);
|
||||||
|
return std::string(ts) + " ";
|
||||||
|
}
|
||||||
|
|
||||||
|
void setGuidanceStep(int step, int totalSteps) {
|
||||||
|
struct timespec now;
|
||||||
|
clock_gettime(CLOCK_MONOTONIC, &now);
|
||||||
|
|
||||||
|
// From step 2 onward, elapsed = setGuidanceStep(N-1) → setGuidanceStep(N),
|
||||||
|
// which spans the full prior iteration: guidance computation + target send
|
||||||
|
// + flight + position request/receive.
|
||||||
|
if (step > 1 && lastStepTime.tv_sec != 0) {
|
||||||
|
double elapsed = (now.tv_sec - lastStepTime.tv_sec)
|
||||||
|
+ (now.tv_nsec - lastStepTime.tv_nsec) * 1e-9;
|
||||||
|
guidanceStep = step;
|
||||||
|
guidanceTotalSteps = totalSteps;
|
||||||
|
std::cout << logPrefix() << "Iteration duration: " << elapsed << " s\n";
|
||||||
|
} else {
|
||||||
|
guidanceStep = step;
|
||||||
|
guidanceTotalSteps = totalSteps;
|
||||||
|
}
|
||||||
|
|
||||||
|
lastStepTime = now;
|
||||||
|
}
|
||||||
|
|
||||||
void initSockets() {}
|
void initSockets() {}
|
||||||
void cleanupSockets() {}
|
void cleanupSockets() {}
|
||||||
@@ -186,7 +224,10 @@ static int readScenarioDataRow(const char* filename, char* line, int lineSize) {
|
|||||||
// 35-37: domainMax (east, north, up)
|
// 35-37: domainMax (east, north, up)
|
||||||
// 38-39: objectivePos (east, north)
|
// 38-39: objectivePos (east, north)
|
||||||
// 40-43: objectiveVar (2x2 col-major: v11, v12, v21, v22)
|
// 40-43: objectiveVar (2x2 col-major: v11, v12, v21, v22)
|
||||||
// 44 : sensorPerformanceMinimum
|
// 44 : sensorPerformanceMinimum (CSV column 18)
|
||||||
|
// 45 : useDoubleIntegrator (CSV column 23; 0=single-integrator, 1=double-integrator)
|
||||||
|
// 46 : dampingCoeff (CSV column 24)
|
||||||
|
// 47 : useFixedTopology (CSV column 25; 0=dynamic lesser-neighbor, 1=fixed)
|
||||||
// Returns 1 on success, 0 on failure.
|
// Returns 1 on success, 0 on failure.
|
||||||
int loadScenario(const char* filename, double* params) {
|
int loadScenario(const char* filename, double* params) {
|
||||||
char line[4096];
|
char line[4096];
|
||||||
@@ -198,8 +239,8 @@ int loadScenario(const char* filename, double* params) {
|
|||||||
|
|
||||||
char* fields[32];
|
char* fields[32];
|
||||||
int nf = splitCSVRow(copy, fields, 32);
|
int nf = splitCSVRow(copy, fields, 32);
|
||||||
if (nf < 19) {
|
if (nf < 26) {
|
||||||
fprintf(stderr, "loadScenario: expected >=19 columns, got %d\n", nf);
|
fprintf(stderr, "loadScenario: expected >=26 columns, got %d\n", nf);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -290,6 +331,24 @@ int loadScenario(const char* filename, double* params) {
|
|||||||
params[44] = atof(trimField(tmp));
|
params[44] = atof(trimField(tmp));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// useDoubleIntegrator: column 23
|
||||||
|
{
|
||||||
|
char tmp[64]; strncpy(tmp, fields[23], sizeof(tmp) - 1); tmp[sizeof(tmp)-1] = '\0';
|
||||||
|
params[45] = atof(trimField(tmp));
|
||||||
|
}
|
||||||
|
|
||||||
|
// dampingCoeff: column 24
|
||||||
|
{
|
||||||
|
char tmp[64]; strncpy(tmp, fields[24], sizeof(tmp) - 1); tmp[sizeof(tmp)-1] = '\0';
|
||||||
|
params[46] = atof(trimField(tmp));
|
||||||
|
}
|
||||||
|
|
||||||
|
// useFixedTopology: column 25
|
||||||
|
{
|
||||||
|
char tmp[64]; strncpy(tmp, fields[25], sizeof(tmp) - 1); tmp[sizeof(tmp)-1] = '\0';
|
||||||
|
params[47] = atof(trimField(tmp));
|
||||||
|
}
|
||||||
|
|
||||||
printf("Loaded scenario: domain [%g,%g,%g] to [%g,%g,%g]\n",
|
printf("Loaded scenario: domain [%g,%g,%g] to [%g,%g,%g]\n",
|
||||||
params[32], params[33], params[34], params[35], params[36], params[37]);
|
params[32], params[33], params[34], params[35], params[36], params[37]);
|
||||||
return 1;
|
return 1;
|
||||||
@@ -430,18 +489,22 @@ static const char* messageTypeName(uint8_t msgType) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send a single-byte message type to a client
|
// Send a single-byte message type to a client (no logging)
|
||||||
int sendMessageType(int clientId, int msgType) {
|
static int sendMessageTypeRaw(int clientId, int msgType) {
|
||||||
if (clientId <= 0 || clientId > (int)clientSockets.size()) return 0;
|
if (clientId <= 0 || clientId > (int)clientSockets.size()) return 0;
|
||||||
|
|
||||||
uint8_t msg = (uint8_t)msgType;
|
uint8_t msg = (uint8_t)msgType;
|
||||||
ssize_t sent = send(clientSockets[clientId - 1], &msg, 1, 0);
|
ssize_t sent = send(clientSockets[clientId - 1], &msg, 1, 0);
|
||||||
if (sent != 1) {
|
if (sent != 1) {
|
||||||
std::cerr << "Send failed for client " << clientId << "\n";
|
std::cerr << "Send failed for client " << clientId << "\n";
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
std::cout << "Sent " << messageTypeName(msg) << " to client " << clientId << "\n";
|
// Send a single-byte message type to a client
|
||||||
|
int sendMessageType(int clientId, int msgType) {
|
||||||
|
if (!sendMessageTypeRaw(clientId, msgType)) return 0;
|
||||||
|
std::cout << logPrefix() << "Sent " << messageTypeName((uint8_t)msgType) << " to client " << clientId << "\n";
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -460,13 +523,7 @@ int sendTarget(int clientId, const double* coords) {
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Timestamp
|
std::cout << logPrefix() << "Sent TARGET to client " << clientId << ": "
|
||||||
time_t now = time(nullptr);
|
|
||||||
struct tm* lt = localtime(&now);
|
|
||||||
char ts[16];
|
|
||||||
strftime(ts, sizeof(ts), "%H:%M:%S", lt);
|
|
||||||
|
|
||||||
std::cout << ts << " Sent TARGET to client " << clientId << ": "
|
|
||||||
<< coords[0] << "," << coords[1] << "," << coords[2] << "\n";
|
<< coords[0] << "," << coords[1] << "," << coords[2] << "\n";
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
@@ -514,31 +571,36 @@ int waitForAllMessageType(int numClients, int expectedType) {
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::cout << "Received " << messageTypeName(msgType) << " from client " << (i + 1) << "\n";
|
|
||||||
|
|
||||||
if (msgType == expected) {
|
if (msgType == expected) {
|
||||||
completed[i] = true;
|
completed[i] = true;
|
||||||
completedCount++;
|
completedCount++;
|
||||||
|
} else {
|
||||||
|
std::cerr << logPrefix() << "Unexpected " << messageTypeName(msgType)
|
||||||
|
<< " from client " << (i + 1)
|
||||||
|
<< " (expected " << messageTypeName(expected) << ")\n";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
std::cout << logPrefix() << "Received " << messageTypeName(expected) << " from all clients\n";
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Broadcast GUIDANCE_TOGGLE to all clients
|
// Broadcast GUIDANCE_TOGGLE to all clients
|
||||||
void sendGuidanceToggle(int numClients) {
|
void sendGuidanceToggle(int numClients) {
|
||||||
for (int i = 1; i <= numClients; i++) {
|
for (int i = 1; i <= numClients; i++) {
|
||||||
sendMessageType(i, 6); // GUIDANCE_TOGGLE = 6
|
sendMessageTypeRaw(i, 6); // GUIDANCE_TOGGLE = 6
|
||||||
}
|
}
|
||||||
|
std::cout << logPrefix() << "Sent GUIDANCE_TOGGLE to clients\n";
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send REQUEST_POSITION to all clients
|
// Send REQUEST_POSITION to all clients
|
||||||
int sendRequestPositions(int numClients) {
|
int sendRequestPositions(int numClients) {
|
||||||
for (int i = 1; i <= numClients; i++) {
|
for (int i = 1; i <= numClients; i++) {
|
||||||
if (!sendMessageType(i, 7)) return 0; // REQUEST_POSITION = 7
|
if (!sendMessageTypeRaw(i, 7)) return 0; // REQUEST_POSITION = 7
|
||||||
}
|
}
|
||||||
|
std::cout << logPrefix() << "Sent REQUEST_POSITION to clients\n";
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -573,7 +635,7 @@ int recvPositions(int numClients, double* positions, int maxClients) {
|
|||||||
positions[i + 1 * maxClients] = coords[1]; // north (y)
|
positions[i + 1 * maxClients] = coords[1]; // north (y)
|
||||||
positions[i + 2 * maxClients] = coords[2]; // up (z)
|
positions[i + 2 * maxClients] = coords[2]; // up (z)
|
||||||
|
|
||||||
std::cout << "Position from client " << (i + 1) << ": "
|
std::cout << logPrefix() << "Position from client " << (i + 1) << ": "
|
||||||
<< coords[0] << "," << coords[1] << "," << coords[2] << "\n";
|
<< coords[0] << "," << coords[1] << "," << coords[2] << "\n";
|
||||||
}
|
}
|
||||||
return 1;
|
return 1;
|
||||||
|
|||||||
@@ -30,7 +30,10 @@ int loadTargets(const char* filename, double* targets, int maxClients);
|
|||||||
// 38-39 objectivePos
|
// 38-39 objectivePos
|
||||||
// 40-43 objectiveVar (2x2 col-major)
|
// 40-43 objectiveVar (2x2 col-major)
|
||||||
// 44 sensorPerformanceMinimum
|
// 44 sensorPerformanceMinimum
|
||||||
#define NUM_SCENARIO_PARAMS 45
|
// 45 useDoubleIntegrator (0=single-integrator, 1=double-integrator)
|
||||||
|
// 46 dampingCoeff
|
||||||
|
// 47 useFixedTopology (0=dynamic lesser-neighbor, 1=fixed)
|
||||||
|
#define NUM_SCENARIO_PARAMS 48
|
||||||
#define MAX_CLIENTS_PER_PARAM 4
|
#define MAX_CLIENTS_PER_PARAM 4
|
||||||
// Maximum number of obstacles (upper bound for pre-allocated arrays).
|
// Maximum number of obstacles (upper bound for pre-allocated arrays).
|
||||||
#define MAX_OBSTACLES 8
|
#define MAX_OBSTACLES 8
|
||||||
@@ -59,6 +62,7 @@ int sendTarget(int clientId, const double* coords);
|
|||||||
int waitForAllMessageType(int numClients, int expectedType);
|
int waitForAllMessageType(int numClients, int expectedType);
|
||||||
|
|
||||||
// Guidance loop operations
|
// Guidance loop operations
|
||||||
|
void setGuidanceStep(int step, int totalSteps); // call at the top of each guidance iteration
|
||||||
void sendGuidanceToggle(int numClients);
|
void sendGuidanceToggle(int numClients);
|
||||||
int sendRequestPositions(int numClients);
|
int sendRequestPositions(int numClients);
|
||||||
int recvPositions(int numClients, double* positions, int maxClients); // column-major maxClients x 3
|
int recvPositions(int numClients, double* positions, int maxClients); // column-major maxClients x 3
|
||||||
|
|||||||
@@ -13,3 +13,4 @@ cp ../scripts/startVehicle.sh /root/Profiles/ProfileScripts/Vehicle/.
|
|||||||
|
|
||||||
echo "REMEMBER! Manually edit startexperiment.sh to point to the correct client.yaml"
|
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 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"
|
||||||
@@ -1,7 +1,8 @@
|
|||||||
function [f, G] = plotGpsLogs(logDirs, seaToGroundLevel)
|
function [f, G] = plotGpsLogs(logDirs, seaToGroundLevel, plotWholeFlight)
|
||||||
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;
|
||||||
@@ -28,6 +29,7 @@ function [f, G] = plotGpsLogs(logDirs, seaToGroundLevel)
|
|||||||
logDirs = dir(logDirs);
|
logDirs = dir(logDirs);
|
||||||
logDirs = logDirs(3:end);
|
logDirs = logDirs(3:end);
|
||||||
logDirs = logDirs([logDirs.isdir] == 1);
|
logDirs = logDirs([logDirs.isdir] == 1);
|
||||||
|
logDirs = logDirs(~startsWith({logDirs.name}, "controller_"));
|
||||||
|
|
||||||
G = cell(size(logDirs));
|
G = cell(size(logDirs));
|
||||||
for ii = 1:size(logDirs, 1)
|
for ii = 1:size(logDirs, 1)
|
||||||
@@ -48,8 +50,10 @@ function [f, G] = plotGpsLogs(logDirs, seaToGroundLevel)
|
|||||||
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
|
||||||
% startIdx = 1;
|
if plotWholeFlight
|
||||||
% stopIdx = length(verticalSpeed);
|
startIdx = 1;
|
||||||
|
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
|
||||||
@@ -58,6 +62,27 @@ function [f, G] = plotGpsLogs(logDirs, seaToGroundLevel)
|
|||||||
enu = array2table(enu, 'VariableNames', ["East", "North", "Up"]);
|
enu = array2table(enu, 'VariableNames', ["East", "North", "Up"]);
|
||||||
G{ii} = [G{ii}, enu];
|
G{ii} = [G{ii}, enu];
|
||||||
|
|
||||||
|
% Do crude comparison of pairwise distances between this UAV and
|
||||||
|
% all previous UAVs
|
||||||
|
for jj = 1:(ii - 1)
|
||||||
|
Ai = G{ii}(:, [1, end-2:end]);
|
||||||
|
Aj = G{jj}(:, [1, end-2:end]);
|
||||||
|
|
||||||
|
% Trim data to match sizes
|
||||||
|
idx = min([size(Ai, 1), size(Aj, 1)]);
|
||||||
|
Ai = Ai(1:idx, :); Aj = Aj(1:idx, :);
|
||||||
|
|
||||||
|
pos_i = [Ai.East, Ai.North, Ai.Up];
|
||||||
|
pos_j = [Aj.East, Aj.North, Aj.Up];
|
||||||
|
d = vecnorm(pos_i - pos_j, 2, 2);
|
||||||
|
d = d(~isnan(d));
|
||||||
|
|
||||||
|
fprintf("Minimum distance between agents %d and %d is %2.3f\n", ii, jj, min(d));
|
||||||
|
if min(d) < 6
|
||||||
|
warning("Minimum distance between agents %d and %d of %2.3f is questionable for AERPAW", ii, jj, min(d));
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
% Plot recorded trajectory over specified range of indices
|
% Plot recorded trajectory over specified range of indices
|
||||||
geoplot3(gf, G{ii}.Latitude(startIdx:stopIdx), G{ii}.Longitude(startIdx:stopIdx), G{ii}.Altitude(startIdx:stopIdx) + seaToGroundLevel, c(mod(ii, length(c))), 'LineWidth', 2, "MarkerSize", 5);
|
geoplot3(gf, G{ii}.Latitude(startIdx:stopIdx), G{ii}.Longitude(startIdx:stopIdx), G{ii}.Altitude(startIdx:stopIdx) + seaToGroundLevel, c(mod(ii, length(c))), 'LineWidth', 2, "MarkerSize", 5);
|
||||||
end
|
end
|
||||||
|
|||||||
@@ -0,0 +1,32 @@
|
|||||||
|
function T2 = readControllerLogs(filepath)
|
||||||
|
arguments (Input)
|
||||||
|
filepath (1, 1) string;
|
||||||
|
end
|
||||||
|
arguments (Output)
|
||||||
|
T2 table;
|
||||||
|
end
|
||||||
|
assert(isfile(filepath), "File not found at %s", filepath);
|
||||||
|
|
||||||
|
T = readtable(filepath, 'VariableNamingRule', 'preserve');
|
||||||
|
s = split(T.(T.Properties.VariableNames{1}), ']');
|
||||||
|
s2 = strip(s(startsWith(s(:, 2), " ("), 1), 'left', '[');
|
||||||
|
d = datetime(s2, "InputFormat", "yyyy-MM-dd HH:mm:ss.SSSSSS")';
|
||||||
|
it = s(startsWith(s(:, 2), " ("), 2);
|
||||||
|
it = str2double(strip(strip(it, 'left'), 'left', '('));
|
||||||
|
T.Var3 = strip(append(T.Var3, " ", T.Var4, " ", T.Var5, " ", T.Var6, " ", T.Var7));
|
||||||
|
T.Var4 = []; T.Var5 = []; T.Var6 = []; T.Var7 = [];
|
||||||
|
msg = T.(T.Properties.VariableNames{2});
|
||||||
|
msg = msg(startsWith(s(:, 2), " ("), :);
|
||||||
|
s3 = split(msg, ') ');
|
||||||
|
s3 = s3(:, 2);
|
||||||
|
msg = append(s3, T.Var3(startsWith(s(:, 2), " (")));
|
||||||
|
T2 = table(it, d', msg, 'VariableNames', ["iteration", "timestamp", "message"]);
|
||||||
|
% T.Var1 = datetime(strip(strip(append(T.Var1, " ", T.Var2), 'left', '['), 'right', ']'), "InputFormat", "yyyy-MM-dd HH:mm:ss.SSSSSS");
|
||||||
|
% T.Var2 = [];
|
||||||
|
% T.Var3 = strip(append(T.Var3, " ", T.Var4, " ", T.Var5, " ", T.Var6, " ", string(T.Var7), " ", T.Var8, " ", T.Var9));
|
||||||
|
% T.Var4 = []; T.Var5 = []; T.Var6 = []; T.Var7 = []; T.Var8 = []; T.Var9 = [];
|
||||||
|
% T.Properties.VariableNames{1} = 'timestamp';
|
||||||
|
% T.Properties.VariableNames{2} = 'message';
|
||||||
|
|
||||||
|
% T(ismissing(T.message), :) = [];
|
||||||
|
end
|
||||||
@@ -2,7 +2,6 @@ function R = readRadioLogs(logPath)
|
|||||||
arguments (Input)
|
arguments (Input)
|
||||||
logPath (1, 1) string {isfolder(logPath)};
|
logPath (1, 1) string {isfolder(logPath)};
|
||||||
end
|
end
|
||||||
|
|
||||||
arguments (Output)
|
arguments (Output)
|
||||||
R (:, 8) table;
|
R (:, 8) table;
|
||||||
end
|
end
|
||||||
@@ -31,14 +30,26 @@ function R = readRadioLogs(logPath)
|
|||||||
end
|
end
|
||||||
|
|
||||||
fid = fopen(filepath, 'r');
|
fid = fopen(filepath, 'r');
|
||||||
% Skip 3 lines: 2 junk (tail errors) + 1 header (tx_uav_id,value)
|
% Skip header lines: some files have 2 tail-error lines + 1 column
|
||||||
for k = 1:3
|
% header ("tx_uav_id,value"), others start with data immediately.
|
||||||
fgetl(fid);
|
% Read until a line that looks like a data record, then rewind to it.
|
||||||
|
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(data{1}, 'InputFormat', 'yyyy-MM-dd HH:mm:ss.SSSSSS');
|
ts = datetime(cellstr(data{1}), 'InputFormat', 'yyyy-MM-dd HH:mm:ss.SSSSSS');
|
||||||
txId = int32(data{2});
|
txId = int32(data{2});
|
||||||
val = data{3};
|
val = data{3};
|
||||||
|
|
||||||
|
|||||||
@@ -1,9 +1,30 @@
|
|||||||
%% 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", "two_around_wall"); % Define path to results copied from AERPAW platform
|
||||||
|
|
||||||
|
% Measure intervals between issuing commands from the controller
|
||||||
|
% (make sure this is ~4-5 seconds at minimum to avoid overwhelming the UAV autopilot)
|
||||||
|
r = dir(resultsPath);
|
||||||
|
controllerPath = fullfile(r(startsWith({r.name}, 'controller_')).folder, r(startsWith({r.name}, 'controller_')).name);
|
||||||
|
controllerPath = dir(controllerPath);
|
||||||
|
controllerPath = fullfile(controllerPath(endsWith({controllerPath.name}, '_controller_log.txt')).folder, controllerPath(endsWith({controllerPath.name}, '_controller_log.txt')).name);
|
||||||
|
controller = readControllerLogs(controllerPath);
|
||||||
|
rpIdx = startsWith(controller.message, "Iteration duration: ");
|
||||||
|
s = split(controller.message(rpIdx), "Iteration duration: ");
|
||||||
|
s = split(s(:, 2), ' s');
|
||||||
|
s = duration(strcat("00:", s(:, 1)), "InputFormat", "mm:ss.SSS");
|
||||||
|
s.Format = "mm:ss.SSS";
|
||||||
|
fprintf("Minimum command spacing: %2.3f seconds\n", seconds(min(s)));
|
||||||
|
fprintf("Maximum command spacing: %2.3f seconds\n", seconds(max(s)));
|
||||||
|
fprintf("Mean command spacing: %2.3f seconds\n", seconds(mean(s)));
|
||||||
|
fprintf("Median command spacing: %2.3f seconds\n", seconds(median(s)));
|
||||||
|
if seconds(min(s)) < 4
|
||||||
|
warning("Minimum command spacing %2.3f questionably short for AERPAW", seconds(min(s)));
|
||||||
|
end
|
||||||
|
|
||||||
% 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
|
||||||
[fGlobe, G] = plotGpsLogs(resultsPath, seaToGroundLevel);
|
plotWholeFlight = true; % do not attempt to automatically trim initial and final positioning and landing from flight plot (buggy)
|
||||||
|
[fGlobe, G] = plotGpsLogs(resultsPath, seaToGroundLevel, true);
|
||||||
|
|
||||||
% Plot radio statistics
|
% Plot radio statistics
|
||||||
[fRadio, R] = plotRadioLogs(resultsPath);
|
[fRadio, R] = plotRadioLogs(resultsPath);
|
||||||
@@ -21,7 +42,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, [2 2])), domain, params.discretizationStep, params.protectedRange, params.sensorPerformanceMinimum);
|
domain.objective = domain.objective.initialize(objectiveFunctionWrapper(params.objectivePos, reshape(params.objectiveVar, [1, 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)
|
||||||
|
|||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?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/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?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/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?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/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="1" type="DIR_SIGNIFIER"/>
|
|
||||||
@@ -0,0 +1,6 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info>
|
||||||
|
<Category UUID="FileClassCategory">
|
||||||
|
<Label UUID="design"/>
|
||||||
|
</Category>
|
||||||
|
</Info>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="initializeFromInits.m" type="File"/>
|
||||||
@@ -0,0 +1,6 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info>
|
||||||
|
<Category UUID="FileClassCategory">
|
||||||
|
<Label UUID="design"/>
|
||||||
|
</Category>
|
||||||
|
</Info>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="plotFromSimHist.m" type="File"/>
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="1" type="DIR_SIGNIFIER"/>
|
|
||||||
@@ -0,0 +1,6 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info>
|
||||||
|
<Category UUID="FileClassCategory">
|
||||||
|
<Label UUID="design"/>
|
||||||
|
</Category>
|
||||||
|
</Info>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="readControllerLogs.m" type="File"/>
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?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/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?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/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="test4" type="File"/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="test13" type="File"/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="t1" type="File"/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="test14" type="File"/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="test11" type="File"/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="test6" type="File"/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="test3" type="File"/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="test10" type="File"/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="test12" type="File"/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?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/>
|
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<Info location="1" type="DIR_SIGNIFIER"/>
|
|
||||||
@@ -34,7 +34,14 @@ 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");
|
||||||
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper(params.objectivePos, reshape(params.objectiveVar, [2 2])), tc.domain, params.discretizationStep, params.protectedRange, params.sensorPerformanceMinimum);
|
if length(params.objectiveVar) > 4 && length(params.objectivePos) > 2
|
||||||
|
objectiveSigma = permute(reshape(params.objectiveVar, [length(params.objectiveVar)/4 2 2]), [3 1 2]);
|
||||||
|
objectivePos = reshape(params.objectivePos, [length(params.objectivePos)/2, 2])';
|
||||||
|
else
|
||||||
|
objectiveSigma = reshape(params.objectiveVar, [1, 2, 2]);
|
||||||
|
objectivePos = params.objectivePos;
|
||||||
|
end
|
||||||
|
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper(objectivePos, objectiveSigma), tc.domain, params.discretizationStep, params.protectedRange, params.sensorPerformanceMinimum, 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)
|
||||||
@@ -81,7 +88,8 @@ 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");
|
||||||
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([.75 * l, 0.75 * l]), tc.domain, params.discretizationStep(ii), params.protectedRange(ii), params.sensorPerformanceMinimum(ii));
|
objectiveCenter = [.75 * l, 0.75 * l];
|
||||||
|
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);
|
||||||
|
|||||||
+132
-10
@@ -166,8 +166,8 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
end
|
end
|
||||||
|
|
||||||
% Initialize candidate agent collision geometry
|
% Initialize candidate agent collision geometry
|
||||||
candidateGeometry = rectangularPrism;
|
candidateGeometry = spherical;
|
||||||
candidateGeometry = candidateGeometry.initialize([candidatePos - tc.collisionRanges(ii) * ones(1, 3); candidatePos + tc.collisionRanges(ii) * ones(1, 3)], REGION_TYPE.COLLISION);
|
candidateGeometry = candidateGeometry.initialize(candidatePos, tc.collisionRanges(ii), 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));
|
||||||
@@ -437,12 +437,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);
|
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([7, 6]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [7, 6]);
|
||||||
|
|
||||||
% Initialize agent collision geometry
|
% Initialize agent collision geometry
|
||||||
tc.agents = {agent};
|
tc.agents = {agent};
|
||||||
geometry1 = rectangularPrism;
|
geometry1 = spherical;
|
||||||
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);
|
geometry1 = geometry1.initialize([tc.domain.center(1:2)-tc.domain.dimensions(1)/4, 3], tc.collisionRanges(1), 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);
|
||||||
@@ -466,7 +466,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);
|
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([3, 7]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [3, 7]);
|
||||||
|
|
||||||
% Initialize agent collision geometry
|
% Initialize agent collision geometry
|
||||||
tc.agents = {agent; agent};
|
tc.agents = {agent; agent};
|
||||||
@@ -504,7 +504,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);
|
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5.2195]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [8, 5.2195]);
|
||||||
|
|
||||||
% Initialize agent collision geometry
|
% Initialize agent collision geometry
|
||||||
tc.agents = {agent; agent;};
|
tc.agents = {agent; agent;};
|
||||||
@@ -588,7 +588,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);
|
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [8, 5]);
|
||||||
|
|
||||||
% Initialize agent collision geometry
|
% Initialize agent collision geometry
|
||||||
tc.agents = {agent; agent;};
|
tc.agents = {agent; agent;};
|
||||||
@@ -633,7 +633,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);
|
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [8, 5]);
|
||||||
|
|
||||||
% Initialize agent collision geometry
|
% Initialize agent collision geometry
|
||||||
tc.agents = {agent; agent; agent; agent; agent;};
|
tc.agents = {agent; agent; agent; agent; agent;};
|
||||||
@@ -683,7 +683,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);
|
tc.domain.objective = tc.domain.objective.initialize(objectiveFunctionWrapper([8, 5]), tc.domain, tc.discretizationStep, tc.protectedRange, 1e-6, [8, 5]);
|
||||||
|
|
||||||
% 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;};
|
||||||
@@ -728,6 +728,128 @@ 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
|
||||||
|
|||||||
@@ -4,12 +4,16 @@ 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 = reshape(eye(2), 1, 2, 2);
|
||||||
end
|
end
|
||||||
arguments (Output)
|
arguments (Output)
|
||||||
f (1, 1) {mustBeA(f, "function_handle")};
|
f (1, 1) {mustBeA(f, "function_handle")};
|
||||||
end
|
end
|
||||||
|
|
||||||
f = @(x,y) sum(cell2mat(arrayfun(@(i) mvnpdf([x(:), y(:)], center(i,:), sigma), 1:size(center,1), "UniformOutput", false)), 2);
|
if size(sigma, 1) == 1 && size(center, 1) > 1
|
||||||
|
sigma = repmat(sigma, size(center, 1), 1, 1);
|
||||||
|
end
|
||||||
|
|
||||||
|
assert(size(center, 1) == size(sigma, 1));
|
||||||
|
f = @(x,y) sum(cell2mat(arrayfun(@(i) mvnpdf([x(:), y(:)], center(i,:), squeeze(sigma(i, :, :))), 1:size(center,1), "UniformOutput", false)), 2);
|
||||||
end
|
end
|
||||||
Reference in New Issue
Block a user