Compare commits
11 Commits
b09f882369
...
ca891a809f
| Author | SHA1 | Date | |
|---|---|---|---|
| ca891a809f | |||
| 771575560f | |||
| f003528a9c | |||
| 102f23316d | |||
| 24113f282f | |||
| b4cd7613ec | |||
| 97e34264dd | |||
| c5f1dcdb51 | |||
| e5fa2fa827 | |||
| fdd9b49e34 | |||
| ea034dd748 |
@@ -6,6 +6,8 @@ classdef agent
|
|||||||
% State
|
% State
|
||||||
lastPos = NaN(1, 3); % position from previous timestep
|
lastPos = NaN(1, 3); % position from previous timestep
|
||||||
pos = NaN(1, 3); % current position
|
pos = NaN(1, 3); % current position
|
||||||
|
vel = zeros(1, 3); % velocity (double-integrator mode)
|
||||||
|
lastVel = zeros(1, 3); % pre-step velocity (double-integrator mode)
|
||||||
|
|
||||||
% Sensor
|
% Sensor
|
||||||
sensorModel;
|
sensorModel;
|
||||||
|
|||||||
@@ -15,6 +15,8 @@ function obj = initialize(obj, pos, collisionGeometry, sensorModel, comRange, ma
|
|||||||
end
|
end
|
||||||
|
|
||||||
obj.pos = pos;
|
obj.pos = pos;
|
||||||
|
obj.vel = zeros(1, 3);
|
||||||
|
obj.lastVel = zeros(1, 3);
|
||||||
obj.collisionGeometry = collisionGeometry;
|
obj.collisionGeometry = collisionGeometry;
|
||||||
obj.sensorModel = sensorModel;
|
obj.sensorModel = sensorModel;
|
||||||
obj.label = label;
|
obj.label = label;
|
||||||
|
|||||||
36
@agent/run.m
36
@agent/run.m
@@ -1,4 +1,4 @@
|
|||||||
function obj = run(obj, domain, partitioning, timestepIndex, index, agents)
|
function obj = run(obj, domain, partitioning, timestepIndex, index, agents, useDoubleIntegrator, dampingCoeff, dt)
|
||||||
arguments (Input)
|
arguments (Input)
|
||||||
obj (1, 1) {mustBeA(obj, "agent")};
|
obj (1, 1) {mustBeA(obj, "agent")};
|
||||||
domain (1, 1) {mustBeGeometry};
|
domain (1, 1) {mustBeGeometry};
|
||||||
@@ -6,6 +6,9 @@ function obj = run(obj, domain, partitioning, timestepIndex, index, agents)
|
|||||||
timestepIndex (1, 1) double;
|
timestepIndex (1, 1) double;
|
||||||
index (1, 1) double;
|
index (1, 1) double;
|
||||||
agents (:, 1) {mustBeA(agents, "cell")};
|
agents (:, 1) {mustBeA(agents, "cell")};
|
||||||
|
useDoubleIntegrator (1, 1) logical = false;
|
||||||
|
dampingCoeff (1, 1) double = 2.0;
|
||||||
|
dt (1, 1) double = 1.0;
|
||||||
end
|
end
|
||||||
arguments (Output)
|
arguments (Output)
|
||||||
obj (1, 1) {mustBeA(obj, "agent")};
|
obj (1, 1) {mustBeA(obj, "agent")};
|
||||||
@@ -75,19 +78,26 @@ function obj = run(obj, domain, partitioning, timestepIndex, index, agents)
|
|||||||
targetRate = obj.initialStepSize - obj.stepDecayRate * timestepIndex; % slow down as you get closer
|
targetRate = obj.initialStepSize - obj.stepDecayRate * timestepIndex; % slow down as you get closer
|
||||||
gradNorm = norm(gradC);
|
gradNorm = norm(gradC);
|
||||||
|
|
||||||
% Compute unconstrained next position.
|
% Compute unconstrained next state
|
||||||
% Guard against near-zero gradient: when sensor performance is saturated
|
|
||||||
% or near-zero across the whole partition, rateFactor -> Inf and pNext
|
|
||||||
% explodes. Stay put instead.
|
|
||||||
if gradNorm < 1e-100
|
|
||||||
pNext = obj.pos;
|
|
||||||
else
|
|
||||||
pNext = obj.pos + (targetRate / gradNorm) * gradC;
|
|
||||||
end
|
|
||||||
|
|
||||||
% Move to next position
|
|
||||||
obj.lastPos = obj.pos;
|
obj.lastPos = obj.pos;
|
||||||
obj.pos = pNext;
|
if useDoubleIntegrator
|
||||||
|
% Double-integrator: gradient produces desired acceleration with damping
|
||||||
|
obj.lastVel = obj.vel;
|
||||||
|
if gradNorm < 1e-100
|
||||||
|
a_gradient = zeros(1, 3);
|
||||||
|
else
|
||||||
|
% Scale so steady-state step ≈ targetRate (matching SI behavior)
|
||||||
|
a_gradient = (targetRate * dampingCoeff / (gradNorm * dt)) * gradC;
|
||||||
|
end
|
||||||
|
% Semi-implicit Euler: unconditionally stable for any dampingCoeff and dt
|
||||||
|
obj.vel = (obj.vel + a_gradient * dt) / (1 + dampingCoeff * dt);
|
||||||
|
obj.pos = obj.lastPos + obj.vel * dt;
|
||||||
|
else
|
||||||
|
% Single-integrator: gradient directly sets position step
|
||||||
|
if gradNorm >= 1e-100
|
||||||
|
obj.pos = obj.pos + (targetRate / gradNorm) * gradC;
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
% Reinitialize collision geometry in the new position
|
% Reinitialize collision geometry in the new position
|
||||||
d = obj.pos - obj.collisionGeometry.center;
|
d = obj.pos - obj.collisionGeometry.center;
|
||||||
|
|||||||
@@ -8,31 +8,31 @@ function [obj] = constrainMotion(obj)
|
|||||||
|
|
||||||
nAgents = size(obj.agents, 1);
|
nAgents = size(obj.agents, 1);
|
||||||
|
|
||||||
if nAgents < 2
|
% Compute current velocity and desired control input
|
||||||
nAAPairs = 0;
|
v = zeros(nAgents, 3); % current velocity (for drift term in DI mode)
|
||||||
else
|
u_desired = zeros(nAgents, 3); % desired control: velocity (SI) or acceleration (DI)
|
||||||
nAAPairs = nchoosek(nAgents, 2); % unique agent/agent pairs
|
|
||||||
end
|
|
||||||
|
|
||||||
% Compute velocity matrix from unconstrained gradient-ascent step
|
|
||||||
v = zeros(nAgents, 3);
|
|
||||||
for ii = 1:nAgents
|
for ii = 1:nAgents
|
||||||
v(ii, :) = (obj.agents{ii}.pos - obj.agents{ii}.lastPos) ./ obj.timestep;
|
if obj.useDoubleIntegrator
|
||||||
|
v(ii, :) = obj.agents{ii}.lastVel;
|
||||||
|
u_desired(ii, :) = (obj.agents{ii}.vel - obj.agents{ii}.lastVel) / obj.timestep;
|
||||||
|
else
|
||||||
|
v(ii, :) = (obj.agents{ii}.pos - obj.agents{ii}.lastPos) ./ obj.timestep;
|
||||||
|
u_desired(ii, :) = v(ii, :);
|
||||||
|
end
|
||||||
end
|
end
|
||||||
if all(isnan(v), "all") || all(v == zeros(nAgents, 3), "all")
|
if ~obj.useDoubleIntegrator && (all(isnan(v), "all") || all(v == zeros(nAgents, 3), "all"))
|
||||||
% Agents are not attempting to move, so there is no motion to be
|
% Single-integrator: agents are not attempting to move
|
||||||
% constrained
|
return;
|
||||||
|
end
|
||||||
|
if obj.useDoubleIntegrator && all(u_desired == 0, "all") && all(v == 0, "all")
|
||||||
|
% Double-integrator: no desired acceleration and no existing velocity
|
||||||
return;
|
return;
|
||||||
end
|
end
|
||||||
|
|
||||||
% Initialize QP based on number of agents and obstacles
|
% Initialize QP based on number of agents and obstacles
|
||||||
nAOPairs = nAgents * size(obj.obstacles, 1); % unique agent/obstacle pairs
|
|
||||||
nADPairs = nAgents * 6; % agents x (4 walls + 1 floor + 1 ceiling)
|
|
||||||
nLNAPairs = sum(obj.constraintAdjacencyMatrix, "all") - nAgents;
|
|
||||||
total = nAAPairs + nAOPairs + nADPairs + nLNAPairs;
|
|
||||||
kk = 1;
|
kk = 1;
|
||||||
A = zeros(total, 3 * nAgents);
|
A = zeros(obj.numBarriers, 3 * nAgents);
|
||||||
b = zeros(total, 1);
|
b = zeros(obj.numBarriers, 1);
|
||||||
|
|
||||||
% Set up collision avoidance constraints
|
% Set up collision avoidance constraints
|
||||||
h = NaN(nAgents, nAgents);
|
h = NaN(nAgents, nAgents);
|
||||||
@@ -60,6 +60,10 @@ function [obj] = constrainMotion(obj)
|
|||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
idx = length(h(triu(true(size(h)), 1)));
|
||||||
|
obj.barriers(1:idx, obj.timestepIndex) = h(triu(true(size(h)), 1));
|
||||||
|
idx = idx + 1;
|
||||||
|
|
||||||
hObs = NaN(nAgents, size(obj.obstacles, 1));
|
hObs = NaN(nAgents, size(obj.obstacles, 1));
|
||||||
% Set up obstacle avoidance constraints
|
% Set up obstacle avoidance constraints
|
||||||
for ii = 1:nAgents
|
for ii = 1:nAgents
|
||||||
@@ -80,6 +84,9 @@ function [obj] = constrainMotion(obj)
|
|||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
obj.barriers(idx:(idx + numel(hObs) - 1), obj.timestepIndex) = reshape(hObs, [], 1);
|
||||||
|
idx = idx + numel(hObs);
|
||||||
|
|
||||||
% Set up domain constraints (walls and ceiling only)
|
% Set up domain constraints (walls and ceiling only)
|
||||||
% Floor constraint is implicit with an obstacle corresponding to the
|
% Floor constraint is implicit with an obstacle corresponding to the
|
||||||
% minimum allowed altitude, but I included it anyways
|
% minimum allowed altitude, but I included it anyways
|
||||||
@@ -120,6 +127,9 @@ function [obj] = constrainMotion(obj)
|
|||||||
A(kk, (3 * ii - 2):(3 * ii)) = [0, 0, 1];
|
A(kk, (3 * ii - 2):(3 * ii)) = [0, 0, 1];
|
||||||
b(kk) = obj.barrierGain * max(0, h_zMax)^obj.barrierExponent;
|
b(kk) = obj.barrierGain * max(0, h_zMax)^obj.barrierExponent;
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
|
|
||||||
|
obj.barriers(idx:(idx + 5), obj.timestepIndex) = [h_xMin; h_xMax; h_yMin; h_yMax; h_zMin; h_zMax];
|
||||||
|
idx = idx + 6;
|
||||||
end
|
end
|
||||||
|
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
@@ -133,21 +143,41 @@ function [obj] = constrainMotion(obj)
|
|||||||
for ii = 1:(nAgents - 1)
|
for ii = 1:(nAgents - 1)
|
||||||
for jj = (ii + 1):nAgents
|
for jj = (ii + 1):nAgents
|
||||||
if obj.constraintAdjacencyMatrix(ii, jj)
|
if obj.constraintAdjacencyMatrix(ii, jj)
|
||||||
hComms(ii, jj) = min([obj.agents{ii}.commsGeometry.radius, obj.agents{jj}.commsGeometry.radius])^2 - norm(obj.agents{ii}.pos - obj.agents{jj}.pos)^2;
|
paddingFactor = 0.9; % Barrier at 90% of actual range; real comms still work beyond this
|
||||||
|
r_comms = paddingFactor * min([obj.agents{ii}.commsGeometry.radius, obj.agents{jj}.commsGeometry.radius]);
|
||||||
|
hComms(ii, jj) = r_comms^2 - norm(obj.agents{ii}.pos - obj.agents{jj}.pos)^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}.pos - obj.agents{jj}.pos);
|
||||||
A(kk, (3 * jj - 2):(3 * jj)) = -A(kk, (3 * ii - 2):(3 * ii));
|
A(kk, (3 * jj - 2):(3 * jj)) = -A(kk, (3 * ii - 2):(3 * ii));
|
||||||
b(kk) = obj.barrierGain * max(0, hComms(ii, jj))^obj.barrierExponent;
|
|
||||||
|
% One-step forward invariance: b = h/dt ensures h cannot
|
||||||
|
% go negative in a single timestep (linear approximation)
|
||||||
|
v_max_ij = max(obj.agents{ii}.initialStepSize, obj.agents{jj}.initialStepSize) / obj.timestep;
|
||||||
|
hMin = -4 * r_comms * v_max_ij * obj.timestep;
|
||||||
|
if norm(A(kk, :)) < 1e-9
|
||||||
|
b(kk) = 0;
|
||||||
|
else
|
||||||
|
b(kk) = max(hMin, hComms(ii, jj)) / obj.timestep;
|
||||||
|
end
|
||||||
|
|
||||||
kk = kk + 1;
|
kk = kk + 1;
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
obj.barriers(idx:(idx + length(hComms(triu(true(size(hComms)), 1))) - 1), obj.timestepIndex) = hComms(triu(true(size(hComms)), 1));
|
||||||
|
|
||||||
% Solve QP program generated earlier
|
% Double-integrator: transform QP from velocity to acceleration space.
|
||||||
vhat = reshape(v', 3 * nAgents, 1);
|
% Single-integrator constraint: A * v <= b
|
||||||
|
% Double-integrator: A * a <= (b - A * v_current) / dt
|
||||||
|
if obj.useDoubleIntegrator
|
||||||
|
v_flat = reshape(v', 3 * nAgents, 1);
|
||||||
|
b = (b - A * v_flat) / obj.timestep;
|
||||||
|
end
|
||||||
|
|
||||||
|
% Solve QP: minimize ||u - u_desired||²
|
||||||
|
uhat = reshape(u_desired', 3 * nAgents, 1);
|
||||||
H = 2 * eye(3 * nAgents);
|
H = 2 * eye(3 * nAgents);
|
||||||
f = -2 * vhat;
|
f = -2 * uhat;
|
||||||
|
|
||||||
% Update solution based on constraints
|
% Update solution based on constraints
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
@@ -157,8 +187,8 @@ function [obj] = constrainMotion(obj)
|
|||||||
end
|
end
|
||||||
opt = optimoptions("quadprog", "Display", "off", "Algorithm", "active-set", "UseCodegenSolver", true);
|
opt = optimoptions("quadprog", "Display", "off", "Algorithm", "active-set", "UseCodegenSolver", true);
|
||||||
x0 = zeros(size(H, 1), 1);
|
x0 = zeros(size(H, 1), 1);
|
||||||
[vNew, ~, exitflag] = quadprog(H, double(f), A, b, [], [], [], [], x0, opt);
|
[uNew, ~, exitflag] = quadprog(H, double(f), A, b, [], [], [], [], x0, opt);
|
||||||
vNew = reshape(vNew, 3, nAgents)';
|
uNew = reshape(uNew, 3, nAgents)';
|
||||||
|
|
||||||
if exitflag < 0
|
if exitflag < 0
|
||||||
% Infeasible or other hard failure: hold all agents at current positions
|
% Infeasible or other hard failure: hold all agents at current positions
|
||||||
@@ -167,9 +197,9 @@ function [obj] = constrainMotion(obj)
|
|||||||
else
|
else
|
||||||
fprintf("[constrainMotion] QP infeasible (exitflag=%d), holding positions\n", int16(exitflag));
|
fprintf("[constrainMotion] QP infeasible (exitflag=%d), holding positions\n", int16(exitflag));
|
||||||
end
|
end
|
||||||
vNew = zeros(nAgents, 3);
|
uNew = zeros(nAgents, 3);
|
||||||
elseif exitflag == 0
|
elseif exitflag == 0
|
||||||
% Max iterations exceeded: use suboptimal solution already in vNew
|
% Max iterations exceeded: use suboptimal solution already in uNew
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
warning("QP max iterations exceeded, using suboptimal solution.");
|
warning("QP max iterations exceeded, using suboptimal solution.");
|
||||||
else
|
else
|
||||||
@@ -177,10 +207,16 @@ function [obj] = constrainMotion(obj)
|
|||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
% Update the "next position" that was previously set by unconstrained
|
% Update agent state using the constrained control input
|
||||||
% GA using the constrained solution produced here
|
for ii = 1:size(uNew, 1)
|
||||||
for ii = 1:size(vNew, 1)
|
if obj.useDoubleIntegrator
|
||||||
obj.agents{ii}.pos = obj.agents{ii}.lastPos + vNew(ii, :) * obj.timestep;
|
% uNew is constrained acceleration
|
||||||
|
obj.agents{ii}.vel = obj.agents{ii}.lastVel + uNew(ii, :) * obj.timestep;
|
||||||
|
obj.agents{ii}.pos = obj.agents{ii}.lastPos + obj.agents{ii}.vel * obj.timestep;
|
||||||
|
else
|
||||||
|
% uNew is constrained velocity
|
||||||
|
obj.agents{ii}.pos = obj.agents{ii}.lastPos + uNew(ii, :) * obj.timestep;
|
||||||
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
% Here we run this at the simulation level, but in reality there is no
|
% Here we run this at the simulation level, but in reality there is no
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, minAlt, timestep, maxIter, obstacles, makePlots, makeVideo)
|
function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, minAlt, timestep, maxIter, obstacles, makePlots, makeVideo, useDoubleIntegrator, dampingCoeff, useFixedTopology)
|
||||||
arguments (Input)
|
arguments (Input)
|
||||||
obj (1, 1) {mustBeA(obj, "miSim")};
|
obj (1, 1) {mustBeA(obj, "miSim")};
|
||||||
domain (1, 1) {mustBeGeometry};
|
domain (1, 1) {mustBeGeometry};
|
||||||
@@ -11,6 +11,9 @@ function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, m
|
|||||||
obstacles (:, 1) cell {mustBeGeometry} = cell(0, 1);
|
obstacles (:, 1) cell {mustBeGeometry} = cell(0, 1);
|
||||||
makePlots(1, 1) logical = true;
|
makePlots(1, 1) logical = true;
|
||||||
makeVideo (1, 1) logical = true;
|
makeVideo (1, 1) logical = true;
|
||||||
|
useDoubleIntegrator (1, 1) logical = false;
|
||||||
|
dampingCoeff (1, 1) double = 2.0;
|
||||||
|
useFixedTopology (1, 1) logical = false;
|
||||||
end
|
end
|
||||||
arguments (Output)
|
arguments (Output)
|
||||||
obj (1, 1) {mustBeA(obj, "miSim")};
|
obj (1, 1) {mustBeA(obj, "miSim")};
|
||||||
@@ -86,9 +89,18 @@ function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, m
|
|||||||
obj.barrierExponent = barrierExponent;
|
obj.barrierExponent = barrierExponent;
|
||||||
obj.minAlt = minAlt;
|
obj.minAlt = minAlt;
|
||||||
|
|
||||||
% Compute adjacency matrix and lesser neighbors
|
% Set dynamics model
|
||||||
|
obj.useDoubleIntegrator = useDoubleIntegrator;
|
||||||
|
obj.dampingCoeff = dampingCoeff;
|
||||||
|
obj.useFixedTopology = useFixedTopology;
|
||||||
|
|
||||||
|
% Compute adjacency matrix and network topology
|
||||||
obj = obj.updateAdjacency();
|
obj = obj.updateAdjacency();
|
||||||
obj = obj.lesserNeighbor();
|
if obj.useFixedTopology
|
||||||
|
obj.constraintAdjacencyMatrix = obj.adjacency;
|
||||||
|
else
|
||||||
|
obj = obj.lesserNeighbor();
|
||||||
|
end
|
||||||
|
|
||||||
% Set up times to iterate over
|
% Set up times to iterate over
|
||||||
obj.times = linspace(0, obj.timestep * obj.maxIter, obj.maxIter+1)';
|
obj.times = linspace(0, obj.timestep * obj.maxIter, obj.maxIter+1)';
|
||||||
@@ -104,11 +116,28 @@ function [obj] = initialize(obj, domain, agents, barrierGain, barrierExponent, m
|
|||||||
% Create initial partitioning
|
% Create initial partitioning
|
||||||
obj.partitioning = obj.agents{1}.partition(obj.agents, obj.domain.objective);
|
obj.partitioning = obj.agents{1}.partition(obj.agents, obj.domain.objective);
|
||||||
|
|
||||||
|
% Determine number of barrier functions that will be necessary
|
||||||
|
if size(obj.agents, 1) < 2
|
||||||
|
nAAPairs = 0;
|
||||||
|
else
|
||||||
|
nAAPairs = nchoosek(size(obj.agents, 1), 2); % unique agent/agent pairs
|
||||||
|
end
|
||||||
|
nAOPairs = size(obj.agents, 1) * size(obj.obstacles, 1); % unique agent/obstacle pairs
|
||||||
|
nADPairs = size(obj.agents, 1) * 6; % agents x (4 walls + 1 floor + 1 ceiling)
|
||||||
|
nLNAPairs = sum(triu(obj.constraintAdjacencyMatrix, 1), "all");
|
||||||
|
obj.numBarriers = nAAPairs + nAOPairs + nADPairs + nLNAPairs;
|
||||||
|
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
% Initialize variable that will store agent positions for trail plots
|
% Initialize variable that will store agent positions for trail plots
|
||||||
obj.posHist = NaN(size(obj.agents, 1), obj.maxIter + 1, 3);
|
obj.posHist = NaN(size(obj.agents, 1), obj.maxIter + 1, 3);
|
||||||
obj.posHist(1:size(obj.agents, 1), 1, 1:3) = reshape(cell2mat(cellfun(@(x) x.pos, obj.agents, "UniformOutput", false)), size(obj.agents, 1), 1, 3);
|
obj.posHist(1:size(obj.agents, 1), 1, 1:3) = reshape(cell2mat(cellfun(@(x) x.pos, obj.agents, "UniformOutput", false)), size(obj.agents, 1), 1, 3);
|
||||||
|
|
||||||
|
% Initialize velocity history (zeros at t=0, all agents start at rest)
|
||||||
|
obj.velHist = zeros(size(obj.agents, 1), obj.maxIter + 1, 3);
|
||||||
|
|
||||||
|
% Initialize variable that will store barrier function values per timestep for analysis purposes
|
||||||
|
obj.barriers = NaN(obj.numBarriers, size(obj.times, 1));
|
||||||
|
|
||||||
% Set up plots showing initialized state
|
% Set up plots showing initialized state
|
||||||
obj = obj.plot();
|
obj = obj.plot();
|
||||||
|
|
||||||
|
|||||||
@@ -79,6 +79,23 @@ assert(numel(BETA_TILT_VEC) == numAgents, ...
|
|||||||
|
|
||||||
numObstacles = scenario.numObstacles;
|
numObstacles = scenario.numObstacles;
|
||||||
|
|
||||||
|
% Dynamics model (optional columns — backward compatible with older CSVs)
|
||||||
|
if isfield(scenario, 'useDoubleIntegrator')
|
||||||
|
USE_DOUBLE_INTEGRATOR = logical(scenario.useDoubleIntegrator);
|
||||||
|
else
|
||||||
|
USE_DOUBLE_INTEGRATOR = false;
|
||||||
|
end
|
||||||
|
if isfield(scenario, 'dampingCoeff')
|
||||||
|
DAMPING_COEFF = scenario.dampingCoeff;
|
||||||
|
else
|
||||||
|
DAMPING_COEFF = 2.0;
|
||||||
|
end
|
||||||
|
if isfield(scenario, 'useFixedTopology')
|
||||||
|
USE_FIXED_TOPOLOGY = logical(scenario.useFixedTopology);
|
||||||
|
else
|
||||||
|
USE_FIXED_TOPOLOGY = false;
|
||||||
|
end
|
||||||
|
|
||||||
% ---- Build domain --------------------------------------------------------
|
% ---- Build domain --------------------------------------------------------
|
||||||
dom = rectangularPrism;
|
dom = rectangularPrism;
|
||||||
dom = dom.initialize([DOMAIN_MIN; DOMAIN_MAX], REGION_TYPE.DOMAIN, "Guidance Domain");
|
dom = dom.initialize([DOMAIN_MIN; DOMAIN_MAX], REGION_TYPE.DOMAIN, "Guidance Domain");
|
||||||
@@ -124,6 +141,7 @@ end
|
|||||||
|
|
||||||
% ---- Initialise simulation (plots and video disabled) --------------------
|
% ---- Initialise simulation (plots and video disabled) --------------------
|
||||||
obj = obj.initialize(dom, agentList, BARRIER_GAIN, BARRIER_EXPONENT, ...
|
obj = obj.initialize(dom, agentList, BARRIER_GAIN, BARRIER_EXPONENT, ...
|
||||||
MIN_ALT, TIMESTEP, MAX_ITER, obstacleList, false, false);
|
MIN_ALT, TIMESTEP, MAX_ITER, obstacleList, false, false, ...
|
||||||
|
USE_DOUBLE_INTEGRATOR, DAMPING_COEFF, USE_FIXED_TOPOLOGY);
|
||||||
|
|
||||||
end
|
end
|
||||||
|
|||||||
@@ -18,11 +18,16 @@ classdef miSim
|
|||||||
barrierGain = NaN; % CBF gain parameter
|
barrierGain = NaN; % CBF gain parameter
|
||||||
barrierExponent = NaN; % CBF exponent parameter
|
barrierExponent = NaN; % CBF exponent parameter
|
||||||
minAlt = 0; % minimum allowable altitude (m)
|
minAlt = 0; % minimum allowable altitude (m)
|
||||||
|
useDoubleIntegrator = false; % false = single-integrator, true = double-integrator dynamics
|
||||||
|
dampingCoeff = 2.0; % velocity-proportional damping for double-integrator mode
|
||||||
|
useFixedTopology = false; % false = lesser neighbor (dynamic), true = fixed initial topology
|
||||||
artifactName = "";
|
artifactName = "";
|
||||||
f; % main plotting tiled layout figure
|
f; % main plotting tiled layout figure
|
||||||
fPerf; % performance plot figure
|
fPerf; % performance plot figure
|
||||||
% Indicies for various plot types in the main tiled layout figure
|
% Indicies for various plot types in the main tiled layout figure
|
||||||
spatialPlotIndices = [6, 4, 3, 2];
|
spatialPlotIndices = [6, 4, 3, 2];
|
||||||
|
numBarriers = 0; % Number of barrier functions needed
|
||||||
|
barriers = []; % log barrier function values at each timestep for analysis
|
||||||
end
|
end
|
||||||
|
|
||||||
properties (Access = private)
|
properties (Access = private)
|
||||||
@@ -40,6 +45,7 @@ classdef miSim
|
|||||||
performancePlot; % objects for sensor performance plot
|
performancePlot; % objects for sensor performance plot
|
||||||
|
|
||||||
posHist; % data for trail plot
|
posHist; % data for trail plot
|
||||||
|
velHist; % velocity history (double-integrator mode)
|
||||||
trailPlot; % objects for agent trail plot
|
trailPlot; % objects for agent trail plot
|
||||||
|
|
||||||
% Indicies for various plot types in the main tiled layout figure
|
% Indicies for various plot types in the main tiled layout figure
|
||||||
|
|||||||
11
@miSim/run.m
11
@miSim/run.m
@@ -30,12 +30,14 @@ function [obj] = run(obj)
|
|||||||
obj.partitioning = obj.agents{1}.partition(obj.agents, obj.domain.objective);
|
obj.partitioning = obj.agents{1}.partition(obj.agents, obj.domain.objective);
|
||||||
|
|
||||||
% Determine desired communications links
|
% Determine desired communications links
|
||||||
obj = obj.lesserNeighbor();
|
if ~obj.useFixedTopology
|
||||||
|
obj = obj.lesserNeighbor();
|
||||||
|
end
|
||||||
|
|
||||||
% Moving
|
% Moving
|
||||||
% Iterate over agents to simulate their unconstrained motion
|
% Iterate over agents to simulate their unconstrained motion
|
||||||
for jj = 1:size(obj.agents, 1)
|
for jj = 1:size(obj.agents, 1)
|
||||||
obj.agents{jj} = obj.agents{jj}.run(obj.domain, obj.partitioning, obj.timestepIndex, jj, obj.agents);
|
obj.agents{jj} = obj.agents{jj}.run(obj.domain, obj.partitioning, obj.timestepIndex, jj, obj.agents, obj.useDoubleIntegrator, obj.dampingCoeff, obj.timestep);
|
||||||
end
|
end
|
||||||
|
|
||||||
% Adjust motion determined by unconstrained gradient ascent using
|
% Adjust motion determined by unconstrained gradient ascent using
|
||||||
@@ -43,8 +45,9 @@ function [obj] = run(obj)
|
|||||||
obj = constrainMotion(obj);
|
obj = constrainMotion(obj);
|
||||||
|
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
% Update agent position history array
|
% Update agent position and velocity history arrays
|
||||||
obj.posHist(1:size(obj.agents, 1), obj.timestepIndex + 1, 1:3) = reshape(cell2mat(cellfun(@(x) x.pos, obj.agents, "UniformOutput", false)), size(obj.agents, 1), 1, 3);
|
obj.posHist(1:size(obj.agents, 1), obj.timestepIndex + 1, 1:3) = reshape(cell2mat(cellfun(@(x) x.pos, obj.agents, "UniformOutput", false)), size(obj.agents, 1), 1, 3);
|
||||||
|
obj.velHist(1:size(obj.agents, 1), obj.timestepIndex + 1, 1:3) = reshape(cell2mat(cellfun(@(x) x.vel, obj.agents, "UniformOutput", false)), size(obj.agents, 1), 1, 3);
|
||||||
|
|
||||||
% Update total performance
|
% Update total performance
|
||||||
obj.performance = [obj.performance, sum(cellfun(@(x) x.performance(obj.timestepIndex+1), obj.agents))];
|
obj.performance = [obj.performance, sum(cellfun(@(x) x.performance(obj.timestepIndex+1), obj.agents))];
|
||||||
@@ -63,10 +66,12 @@ function [obj] = run(obj)
|
|||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
|
% Close video
|
||||||
if coder.target('MATLAB')
|
if coder.target('MATLAB')
|
||||||
if obj.makeVideo
|
if obj.makeVideo
|
||||||
% Close video file
|
% Close video file
|
||||||
v.close();
|
v.close();
|
||||||
end
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
end
|
end
|
||||||
|
|||||||
@@ -6,10 +6,33 @@ function obj = teardown(obj)
|
|||||||
obj (1, 1) {mustBeA(obj, "miSim")};
|
obj (1, 1) {mustBeA(obj, "miSim")};
|
||||||
end
|
end
|
||||||
|
|
||||||
% Close plots
|
% % Close plots
|
||||||
close(obj.hf);
|
% close(obj.hf);
|
||||||
close(obj.fPerf);
|
% close(obj.fPerf);
|
||||||
close(obj.f);
|
% close(obj.f);
|
||||||
|
|
||||||
|
% Log results into matfile
|
||||||
|
histPath = fullfile(matlab.project.rootProject().RootFolder, "sandbox", strcat(obj.artifactName, "_miSimHist.mat"));
|
||||||
|
out = struct("agent", repmat(struct("pos", [], "vel", [], "perf", [], "sensor", struct("alphaDist", [], "betaDist", [], "alphaTilt", [], "betaTilt", []), "collisionRadius", [], "commsRadius", []), size(obj.agents)), "perf", [], "barriers", [], "useDoubleIntegrator", [], "dampingCoeff", [], "useFixedTopology", []);
|
||||||
|
|
||||||
|
out.perf = obj.performance(1:(end - 1));
|
||||||
|
out.barriers = [zeros(size(obj.barriers(1:end, 1), 1), 1), obj.barriers(1:end, 1:(end - 1))];
|
||||||
|
out.dampingCoeff = obj.dampingCoeff;
|
||||||
|
out.useDoubleIntegrator = obj.useDoubleIntegrator;
|
||||||
|
out.useFixedTopology = obj.useFixedTopology;
|
||||||
|
for ii = 1:size(obj.agents, 1)
|
||||||
|
out.agent(ii).pos = squeeze(obj.posHist(ii, 1:(end - 1), 1:3));
|
||||||
|
out.agent(ii).vel = squeeze(obj.velHist(ii, 1:(end - 1), 1:3));
|
||||||
|
out.agent(ii).perf = obj.agents{ii}.performance(1:(end - 2));
|
||||||
|
out.agent(ii).sensor.alphaDist = obj.agents{ii}.sensorModel.alphaDist;
|
||||||
|
out.agent(ii).sensor.betaDist = obj.agents{ii}.sensorModel.betaDist;
|
||||||
|
out.agent(ii).sensor.alphaTilt = obj.agents{ii}.sensorModel.alphaTilt;
|
||||||
|
out.agent(ii).sensor.betaTilt = obj.agents{ii}.sensorModel.betaTilt;
|
||||||
|
out.agent(ii).collisionRadius = obj.agents{ii}.collisionGeometry.radius;
|
||||||
|
out.agent(ii).commsRadius = obj.agents{ii}.commsGeometry.radius;
|
||||||
|
end
|
||||||
|
|
||||||
|
save(histPath, "out");
|
||||||
|
|
||||||
% reset parameters
|
% reset parameters
|
||||||
obj.timestep = NaN;
|
obj.timestep = NaN;
|
||||||
@@ -25,6 +48,9 @@ function obj = teardown(obj)
|
|||||||
obj.performance = 0;
|
obj.performance = 0;
|
||||||
obj.barrierGain = NaN;
|
obj.barrierGain = NaN;
|
||||||
obj.barrierExponent = NaN;
|
obj.barrierExponent = NaN;
|
||||||
|
obj.useDoubleIntegrator = false;
|
||||||
|
obj.dampingCoeff = 2.0;
|
||||||
|
obj.useFixedTopology = false;
|
||||||
obj.artifactName = "";
|
obj.artifactName = "";
|
||||||
|
|
||||||
end
|
end
|
||||||
@@ -15,16 +15,16 @@ function writeInits(obj)
|
|||||||
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));
|
||||||
|
|
||||||
|
|
||||||
% 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, "minAlt", obj.obstacles{end}.maxCorner(3), ...
|
||||||
"discretizationStep", obj.domain.objective.discretizationStep, "protectedRange", obj.domain.objective.protectedRange, ...
|
"discretizationStep", obj.domain.objective.discretizationStep, "protectedRange", obj.domain.objective.protectedRange, ...
|
||||||
"sensorPerformanceMinimum", obj.domain.objective.sensorPerformanceMinimum, "initialStepSize", initialStepSize, ...
|
"sensorPerformanceMinimum", obj.domain.objective.sensorPerformanceMinimum, "initialStepSize", initialStepSize, ...
|
||||||
"barrierGain", obj.barrierGain, "barrierExponent", obj.barrierExponent, "numObstacles", size(obj.obstacles, 1), ...
|
"barrierGain", obj.barrierGain, "barrierExponent", obj.barrierExponent, "numObstacles", size(obj.obstacles, 1), ...
|
||||||
"numAgents", size(obj.agents, 1), "collisionRadius", collisionRadii, "comRange", comRanges, "alphaDist", alphaDist, ...
|
"numAgents", size(obj.agents, 1), "collisionRadius", collisionRadii, "comRange", comRanges, ...
|
||||||
"betaDist", betaDist, "alphaTilt", alphaTilt, "betaTilt", betaTilt, ...
|
"useDoubleIntegrator", obj.useDoubleIntegrator, "dampingCoeff", obj.dampingCoeff, ...
|
||||||
|
"alphaDist", alphaDist, "betaDist", betaDist, "alphaTilt", alphaTilt, "betaTilt", betaTilt, ...
|
||||||
... % ^^^ PARAMETERS ^^^ | vvv STATES vvv
|
... % ^^^ PARAMETERS ^^^ | vvv STATES vvv
|
||||||
"pos", pos);
|
"pos", pos); % still needs obstacle states and objective state
|
||||||
|
|
||||||
% Save all parameters to output file
|
% Save all parameters to output file
|
||||||
initsFile = strcat(obj.artifactName, "_miSimInits");
|
initsFile = strcat(obj.artifactName, "_miSimInits");
|
||||||
|
|||||||
@@ -12,8 +12,8 @@ tdm:
|
|||||||
|
|
||||||
# ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
|
# ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
|
||||||
origin:
|
origin:
|
||||||
lat: 35.72550610629396
|
lat: 35.72595214250436
|
||||||
lon: -78.70019657805574
|
lon: -78.69917609299937
|
||||||
alt: 0.0 # Alt=0 means ENU z directly becomes target altitude above home
|
alt: 0.0 # Alt=0 means ENU z directly becomes target altitude above home
|
||||||
# Environment-specific settings
|
# Environment-specific settings
|
||||||
environments:
|
environments:
|
||||||
@@ -32,7 +32,7 @@ environments:
|
|||||||
mavlink:
|
mavlink:
|
||||||
ip: "192.168.32.26"
|
ip: "192.168.32.26"
|
||||||
port: 14550
|
port: 14550
|
||||||
# Controller runs on host machine (192.168.122.1 from E-VM perspective)
|
# Controller runs on host machine (192.168.109.1 from E-VM perspective)
|
||||||
controller:
|
controller:
|
||||||
ip: "192.168.122.1"
|
ip: "192.168.109.1"
|
||||||
port: 5000
|
port: 5000
|
||||||
|
|||||||
@@ -12,8 +12,8 @@ tdm:
|
|||||||
|
|
||||||
# ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
|
# ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
|
||||||
origin:
|
origin:
|
||||||
lat: 35.72550610629396
|
lat: 35.72595214250436
|
||||||
lon: -78.70019657805574
|
lon: -78.69917609299937
|
||||||
alt: 0.0 # Alt=0 means ENU z directly becomes target altitude above home
|
alt: 0.0 # Alt=0 means ENU z directly becomes target altitude above home
|
||||||
# Environment-specific settings
|
# Environment-specific settings
|
||||||
environments:
|
environments:
|
||||||
@@ -32,7 +32,7 @@ environments:
|
|||||||
mavlink:
|
mavlink:
|
||||||
ip: "192.168.32.26"
|
ip: "192.168.32.26"
|
||||||
port: 14550
|
port: 14550
|
||||||
# Controller runs on host machine (192.168.122.1 from E-VM perspective)
|
# Controller runs on host machine (192.168.109.1 from E-VM perspective)
|
||||||
controller:
|
controller:
|
||||||
ip: "192.168.122.1"
|
ip: "192.168.109.1"
|
||||||
port: 5000
|
port: 5000
|
||||||
@@ -1,2 +1,2 @@
|
|||||||
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax
|
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax, useDoubleIntegrator, dampingCoeff, useFixedTopology
|
||||||
5, 120, 30.0, 0.1, 1.0, 2.0, 100, 3, "3.0, 3.0", "30.0, 30.0", "80.0, 80.0", "0.25, 0.25", "5.0, 5.0", "0.1, 0.1", "0.0, 0.0, 0.0", "50.0, 50.0, 80.0", "35.0, 35.0", "10, 5, 5, 10", 0.15, "5.0, 10.0, 45.0, 15.0, 10.0, 35.0", 1, "2.0, 15.0, 0.0", "25.0, 25.0, 50.0"
|
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
|
||||||
|
@@ -133,6 +133,11 @@
|
|||||||
<Size type="coderapp.internal.codertype.Dimension"/>
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
<Size type="coderapp.internal.codertype.Dimension"/>
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
</Types>
|
</Types>
|
||||||
|
<Types id="27" type="coderapp.internal.codertype.PrimitiveType">
|
||||||
|
<ClassName>int32</ClassName>
|
||||||
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
|
<Size type="coderapp.internal.codertype.Dimension"/>
|
||||||
|
</Types>
|
||||||
</Types>
|
</Types>
|
||||||
</coderapp.internal.interface.project.Interface>
|
</coderapp.internal.interface.project.Interface>
|
||||||
</MF0>
|
</MF0>
|
||||||
@@ -1094,7 +1099,7 @@
|
|||||||
</Artifacts>
|
</Artifacts>
|
||||||
<BuildFolder type="coderapp.internal.util.mfz.FileSpec"/>
|
<BuildFolder type="coderapp.internal.util.mfz.FileSpec"/>
|
||||||
<Success>true</Success>
|
<Success>true</Success>
|
||||||
<Timestamp>2026-03-03T19:58:03</Timestamp>
|
<Timestamp>2026-03-11T17:11:03</Timestamp>
|
||||||
</MainBuildResult>
|
</MainBuildResult>
|
||||||
</coderapp.internal.mlc.mfz.MatlabCoderProjectState>
|
</coderapp.internal.mlc.mfz.MatlabCoderProjectState>
|
||||||
</MF0>
|
</MF0>
|
||||||
|
|||||||
@@ -1,12 +1,17 @@
|
|||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include "controller.h"
|
#include "controller.h"
|
||||||
#include "controller_impl.h" // TCP implementation header
|
#include "controller_impl.h" // TCP implementation header
|
||||||
|
|
||||||
int main() {
|
int main() {
|
||||||
// Number of clients to handle
|
// Derive numClients from initialPositions in scenario.csv
|
||||||
int numClients = 2; // for now
|
double targets[MAX_CLIENTS_PER_PARAM * 3];
|
||||||
|
int numClients = loadInitialPositions("config/scenario.csv",
|
||||||
std::cout << "Initializing TCP server...\n";
|
targets, MAX_CLIENTS_PER_PARAM);
|
||||||
|
if (numClients < 1) {
|
||||||
|
std::cerr << "Failed to parse numClients from scenario.csv\n";
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
std::cout << "Parsed " << numClients << " UAV(s) from scenario.csv\n";
|
||||||
|
|
||||||
// Call MATLAB-generated server function
|
// Call MATLAB-generated server function
|
||||||
controller(numClients);
|
controller(numClients);
|
||||||
|
|||||||
@@ -20,4 +20,4 @@ else
|
|||||||
fi
|
fi
|
||||||
|
|
||||||
cd $PROFILE_DIR"/SDR_control/Channel_Sounderv3"
|
cd $PROFILE_DIR"/SDR_control/Channel_Sounderv3"
|
||||||
python3 CSwSNRRX.py --freq $RX_FREQ --gainrx $GAIN_RX --noise 0 --args $ARGS --offset $OFFSET --samp-rate $SAMP_RATE --sps $SPS
|
python3 CSwSNRRX.py --freq $RX_FREQ --gainrx $GAIN_RX --noise 0 --args $ARGS --offset $OFFSET --samp-rate $SAMP_RATE --sps $SPS "$@"
|
||||||
@@ -20,4 +20,4 @@ else
|
|||||||
fi
|
fi
|
||||||
|
|
||||||
cd $PROFILE_DIR"/SDR_control/Channel_Sounderv3"
|
cd $PROFILE_DIR"/SDR_control/Channel_Sounderv3"
|
||||||
python3 CSwSNRTX.py --freq $TX_FREQ --gaintx $GAIN_TX --args $ARGS --offset $OFFSET --samp-rate $SAMP_RATE --sps $SPS
|
python3 CSwSNRTX.py --freq $TX_FREQ --gaintx $GAIN_TX --args $ARGS --offset $OFFSET --samp-rate $SAMP_RATE --sps $SPS "$@"
|
||||||
@@ -1,7 +1,15 @@
|
|||||||
#!/bin/bash
|
#!/bin/bash
|
||||||
|
|
||||||
|
# Drop in replacements for channel sounder scripts
|
||||||
cp startchannelsounderRXGRC.sh /root/Profiles/ProfileScripts/Radio/Helpers/.
|
cp startchannelsounderRXGRC.sh /root/Profiles/ProfileScripts/Radio/Helpers/.
|
||||||
cp startchannelsounderTXGRC.sh /root/Profiles/ProfileScripts/Radio/Helpers/.
|
cp startchannelsounderTXGRC.sh /root/Profiles/ProfileScripts/Radio/Helpers/.
|
||||||
|
|
||||||
cp CSwSNRRX.py /root/Profiles/SDR_control/Channel_Sounderv3/.
|
cp CSwSNRRX.py /root/Profiles/SDR_control/Channel_Sounderv3/.
|
||||||
cp CSwSNRTX.py /root/Profiles/SDR_control/Channel_Sounderv3/.
|
cp CSwSNRTX.py /root/Profiles/SDR_control/Channel_Sounderv3/.
|
||||||
|
|
||||||
|
# Replace start scripts
|
||||||
|
cp ../scripts/startexperiment.sh /root/.
|
||||||
|
cp ../scripts/startRadio.sh /root/Profiles/ProfileScripts/Radio/.
|
||||||
|
cp ../scripts/startVehicle.sh /root/Profiles/ProfileScripts/Vehicle/.
|
||||||
|
|
||||||
|
echo "REMEMBER! Manually edit startexperiment.sh to point to the correct client.yaml"
|
||||||
|
echo "REMEMBER! Manually copy startexperiment_controller.sh to startexperiment.sh on the fixed node"
|
||||||
@@ -1,5 +1,5 @@
|
|||||||
%% Plot AERPAW logs (trajectory, radio)
|
%% Plot AERPAW logs (trajectory, radio)
|
||||||
resultsPath = fullfile(matlab.project.rootProject().RootFolder, "sandbox", "t2"); % 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
|
||||||
|
|
||||||
% 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
|
||||||
|
|||||||
@@ -32,8 +32,8 @@ else
|
|||||||
exit 1
|
exit 1
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# Client config file (optional 2nd argument)
|
# Client config file: 2nd argument > AERPAW_CLIENT_CONFIG env var > default
|
||||||
CONFIG_FILE="${2:-config/client.yaml}"
|
CONFIG_FILE="${2:-${AERPAW_CLIENT_CONFIG:-config/client.yaml}}"
|
||||||
if [ ! -f "$CONFIG_FILE" ]; then
|
if [ ! -f "$CONFIG_FILE" ]; then
|
||||||
echo "Error: Config file not found: $CONFIG_FILE"
|
echo "Error: Config file not found: $CONFIG_FILE"
|
||||||
exit 1
|
exit 1
|
||||||
@@ -59,7 +59,7 @@ echo "[run_uav] MAVLink connection: $CONN"
|
|||||||
|
|
||||||
# Run via aerpawlib
|
# Run via aerpawlib
|
||||||
echo "[run_uav] Starting UAV runner..."
|
echo "[run_uav] Starting UAV runner..."
|
||||||
python3 -m aerpawlib \
|
python3 -u -m aerpawlib \
|
||||||
--script client.uav_runner \
|
--script client.uav_runner \
|
||||||
--conn "$CONN" \
|
--conn "$CONN" \
|
||||||
--vehicle drone
|
--vehicle drone
|
||||||
@@ -1,43 +1,100 @@
|
|||||||
#!/bin/bash
|
#!/bin/bash
|
||||||
#RX
|
|
||||||
|
# Derive number of UAVs from scenario.csv
|
||||||
|
NUM_UAVS=$(python3 -c "
|
||||||
|
import csv, os
|
||||||
|
csv_path = '/root/miSim/aerpaw/config/scenario.csv'
|
||||||
|
with open(csv_path, 'r') as f:
|
||||||
|
reader = csv.reader(f, skipinitialspace=True)
|
||||||
|
header = [h.strip() for h in next(reader)]
|
||||||
|
row = next(reader)
|
||||||
|
col = header.index('initialPositions')
|
||||||
|
vals = [v.strip() for v in row[col].strip().split(',') if v.strip()]
|
||||||
|
print(len(vals) // 3)
|
||||||
|
" 2>/dev/null || echo 0)
|
||||||
|
|
||||||
cd $PROFILE_DIR"/ProfileScripts/Radio/Helpers"
|
cd $PROFILE_DIR"/ProfileScripts/Radio/Helpers"
|
||||||
|
|
||||||
screen -S rxGRC -dm \
|
if [ "$NUM_UAVS" -eq 2 ]; then
|
||||||
bash -c "stdbuf -oL -eL ./startchannelsounderRXGRC.sh \
|
# Direct 1-to-1 mode: UAV 0 = TX only, UAV 1 = RX only
|
||||||
2>&1 | ts $TS_FORMAT \
|
echo "[Radio] 2-UAV direct mode: UAV_ID=$UAV_ID"
|
||||||
| tee $RESULTS_DIR/$LOG_PREFIX\_radio_channelsounderrxgrc_log.txt"
|
|
||||||
|
|
||||||
screen -S power -dm \
|
if [ "$UAV_ID" -eq 0 ]; then
|
||||||
bash -c "stdbuf -oL -eL tail -F /root/Power\
|
# TX only (--num-uavs 1 disables TDM muting)
|
||||||
2>&1 | ts $TS_FORMAT \
|
screen -S txGRC -dm \
|
||||||
| tee $RESULTS_DIR/$LOG_PREFIX\_power_log.txt"
|
bash -c "stdbuf -oL -eL ./startchannelsounderTXGRC.sh --num-uavs 1 \
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_radio_channelsoundertxgrc_log.txt"
|
||||||
|
else
|
||||||
|
# RX only (--num-uavs 1 disables TDM tagging)
|
||||||
|
screen -S rxGRC -dm \
|
||||||
|
bash -c "stdbuf -oL -eL ./startchannelsounderRXGRC.sh --num-uavs 1 \
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_radio_channelsounderrxgrc_log.txt"
|
||||||
|
|
||||||
screen -S quality -dm \
|
screen -S power -dm \
|
||||||
bash -c "stdbuf -oL -eL tail -F /root/Quality\
|
bash -c "stdbuf -oL -eL tail -F /root/Power\
|
||||||
2>&1 | ts $TS_FORMAT \
|
2>&1 | ts $TS_FORMAT \
|
||||||
| tee $RESULTS_DIR/$LOG_PREFIX\_quality_log.txt"
|
| tee $RESULTS_DIR/$LOG_PREFIX\_power_log.txt"
|
||||||
|
|
||||||
screen -S snr -dm \
|
screen -S quality -dm \
|
||||||
bash -c "stdbuf -oL -eL tail -F /root/SNR\
|
bash -c "stdbuf -oL -eL tail -F /root/Quality\
|
||||||
2>&1 | ts $TS_FORMAT \
|
2>&1 | ts $TS_FORMAT \
|
||||||
| tee $RESULTS_DIR/$LOG_PREFIX\_snr_log.txt"
|
| tee $RESULTS_DIR/$LOG_PREFIX\_quality_log.txt"
|
||||||
|
|
||||||
screen -S noisefloor -dm \
|
screen -S snr -dm \
|
||||||
bash -c "stdbuf -oL -eL tail -F /root/NoiseFloor\
|
bash -c "stdbuf -oL -eL tail -F /root/SNR\
|
||||||
2>&1 | ts $TS_FORMAT \
|
2>&1 | ts $TS_FORMAT \
|
||||||
| tee $RESULTS_DIR/$LOG_PREFIX\_noisefloor_log.txt"
|
| tee $RESULTS_DIR/$LOG_PREFIX\_snr_log.txt"
|
||||||
|
|
||||||
screen -S freqoffset -dm \
|
screen -S noisefloor -dm \
|
||||||
bash -c "stdbuf -oL -eL tail -F /root/FreqOffset\
|
bash -c "stdbuf -oL -eL tail -F /root/NoiseFloor\
|
||||||
2>&1 | ts $TS_FORMAT \
|
2>&1 | ts $TS_FORMAT \
|
||||||
| tee $RESULTS_DIR/$LOG_PREFIX\_freqoffset_log.txt"
|
| tee $RESULTS_DIR/$LOG_PREFIX\_noisefloor_log.txt"
|
||||||
|
|
||||||
|
screen -S freqoffset -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/FreqOffset\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_freqoffset_log.txt"
|
||||||
|
fi
|
||||||
|
else
|
||||||
|
# 3+ UAVs: full TDM mode — every node runs both TX and RX
|
||||||
|
echo "[Radio] TDM mode: $NUM_UAVS UAVs, UAV_ID=$UAV_ID"
|
||||||
|
|
||||||
#TX
|
screen -S rxGRC -dm \
|
||||||
|
bash -c "stdbuf -oL -eL ./startchannelsounderRXGRC.sh \
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_radio_channelsounderrxgrc_log.txt"
|
||||||
|
|
||||||
|
screen -S power -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/Power\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_power_log.txt"
|
||||||
|
|
||||||
|
screen -S quality -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/Quality\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_quality_log.txt"
|
||||||
|
|
||||||
|
screen -S snr -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/SNR\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_snr_log.txt"
|
||||||
|
|
||||||
|
screen -S noisefloor -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/NoiseFloor\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_noisefloor_log.txt"
|
||||||
|
|
||||||
|
screen -S freqoffset -dm \
|
||||||
|
bash -c "stdbuf -oL -eL tail -F /root/FreqOffset\
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_freqoffset_log.txt"
|
||||||
|
|
||||||
|
screen -S txGRC -dm \
|
||||||
|
bash -c "stdbuf -oL -eL ./startchannelsounderTXGRC.sh \
|
||||||
|
2>&1 | ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_radio_channelsoundertxgrc_log.txt"
|
||||||
|
fi
|
||||||
|
|
||||||
screen -S txGRC -dm \
|
|
||||||
bash -c "stdbuf -oL -eL ./startchannelsounderTXGRC.sh \
|
|
||||||
2>&1 | ts $TS_FORMAT \
|
|
||||||
| tee $RESULTS_DIR/$LOG_PREFIX\_radio_channelsoundertxgrc_log.txt"
|
|
||||||
cd -
|
cd -
|
||||||
|
|||||||
@@ -23,7 +23,7 @@ cd /root/miSim/aerpaw
|
|||||||
|
|
||||||
# Use screen/ts/tee aerpawism from sample script
|
# Use screen/ts/tee aerpawism from sample script
|
||||||
screen -S vehicle -dm \
|
screen -S vehicle -dm \
|
||||||
bash -c "stdbuf -oL -eL ./run_uav.sh testbed /root/miSim/aerpaw/config/client1.yaml \
|
bash -c "stdbuf -oL -eL ./run_uav.sh testbed \
|
||||||
| ts $TS_FORMAT \
|
| ts $TS_FORMAT \
|
||||||
| tee $RESULTS_DIR/$LOG_PREFIX\_vehicle_log.txt"
|
| tee $RESULTS_DIR/$LOG_PREFIX\_vehicle_log.txt"
|
||||||
|
|
||||||
|
|||||||
11
aerpaw/scripts/startVehicle_controller.sh
Executable file
11
aerpaw/scripts/startVehicle_controller.sh
Executable file
@@ -0,0 +1,11 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
|
||||||
|
cd /root/miSim/aerpaw
|
||||||
|
|
||||||
|
# Compile controller
|
||||||
|
/bin/bash compile.sh
|
||||||
|
|
||||||
|
# Run controller
|
||||||
|
./build/controller_app
|
||||||
|
|
||||||
|
cd -
|
||||||
@@ -40,12 +40,9 @@ export LOG_PREFIX="$(date +%Y-%m-%d_%H_%M_%S)"
|
|||||||
export TX_FREQ=3.32e9
|
export TX_FREQ=3.32e9
|
||||||
export RX_FREQ=3.32e9
|
export RX_FREQ=3.32e9
|
||||||
|
|
||||||
|
|
||||||
export PROFILE_DIR=$AERPAW_REPO"/AHN/E-VM/Profile_software"
|
export PROFILE_DIR=$AERPAW_REPO"/AHN/E-VM/Profile_software"
|
||||||
cd $PROFILE_DIR"/ProfileScripts"
|
cd $PROFILE_DIR"/ProfileScripts"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
./Radio/startRadio.sh
|
./Radio/startRadio.sh
|
||||||
#./Traffic/startTraffic.sh
|
#./Traffic/startTraffic.sh
|
||||||
./Vehicle/startVehicle.sh
|
./Vehicle/startVehicle.sh
|
||||||
|
|||||||
47
aerpaw/scripts/startexperiment_controller.sh
Executable file
47
aerpaw/scripts/startexperiment_controller.sh
Executable file
@@ -0,0 +1,47 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
/root/stopexperiment.sh
|
||||||
|
|
||||||
|
source /root/.ap-set-experiment-env.sh
|
||||||
|
source /root/.bashrc
|
||||||
|
|
||||||
|
export AERPAW_REPO=${AERPAW_REPO:-/root/AERPAW-Dev}
|
||||||
|
export AERPAW_PYTHON=${AERPAW_PYTHON:-python3}
|
||||||
|
export PYTHONPATH=/usr/local/lib/python3/dist-packages/
|
||||||
|
export EXP_NUMBER=${EXP_NUMBER:-1}
|
||||||
|
|
||||||
|
if [ "$AP_EXPENV_THIS_CONTAINER_NODE_VEHICLE" == "vehicle_uav" ]; then
|
||||||
|
export VEHICLE_TYPE=drone
|
||||||
|
elif [ "$AP_EXPENV_THIS_CONTAINER_NODE_VEHICLE" == "vehicle_ugv" ]; then
|
||||||
|
export VEHICLE_TYPE=rover
|
||||||
|
else
|
||||||
|
export VEHICLE_TYPE=none
|
||||||
|
fi
|
||||||
|
|
||||||
|
if [ "$AP_EXPENV_SESSION_ENV" == "Virtual" ]; then
|
||||||
|
export LAUNCH_MODE=EMULATION
|
||||||
|
elif [ "$AP_EXPENV_SESSION_ENV" == "Testbed" ]; then
|
||||||
|
export LAUNCH_MODE=TESTBED
|
||||||
|
else
|
||||||
|
export LAUNCH_MODE=none
|
||||||
|
fi
|
||||||
|
|
||||||
|
# prepare results directory
|
||||||
|
export RESULTS_DIR_TIMESTAMP=$(date +%Y-%m-%d_%H_%M_%S)
|
||||||
|
export RESULTS_DIR="/root/Results/controller_${RESULTS_DIR_TIMESTAMP}"
|
||||||
|
mkdir -p "$RESULTS_DIR"
|
||||||
|
|
||||||
|
export TS_FORMAT="${TS_FORMAT:-'[%Y-%m-%d %H:%M:%.S]'}"
|
||||||
|
export LOG_PREFIX="$(date +%Y-%m-%d_%H_%M_%S)"
|
||||||
|
|
||||||
|
export TX_FREQ=3.32e9
|
||||||
|
export RX_FREQ=3.32e9
|
||||||
|
|
||||||
|
export PROFILE_DIR=$AERPAW_REPO"/AHN/E-VM/Profile_software"
|
||||||
|
cd $PROFILE_DIR"/ProfileScripts"
|
||||||
|
|
||||||
|
screen -S controller -dm \
|
||||||
|
bash -c "stdbuf -oL -eL ./Vehicle/startVehicle.sh \
|
||||||
|
| ts $TS_FORMAT \
|
||||||
|
| tee $RESULTS_DIR/$LOG_PREFIX\_controller_log.txt"
|
||||||
|
|
||||||
|
schedule_stop.sh 30
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info Ref="aerpaw/scripts" Type="Relative"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="6402cbb5-c767-4c8b-bd7c-b2d7cf1055fc" type="Reference"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="scripts" type="File"/>
|
||||||
@@ -1,2 +1,2 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
<Info location="t1.zip" type="File"/>
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startexperiment_controller.sh" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startRadio.sh" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="1" type="DIR_SIGNIFIER"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startexperiment.sh" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startVehicle.sh" type="File"/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info/>
|
||||||
@@ -0,0 +1,2 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<Info location="startVehicle_controller.sh" type="File"/>
|
||||||
@@ -57,13 +57,16 @@ classdef parametricTestSuite < matlab.unittest.TestCase
|
|||||||
end
|
end
|
||||||
|
|
||||||
% Set up simulation
|
% Set up simulation
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, agents, params.barrierGain, params.barrierExponent, params.minAlt, params.timestep, params.maxIter, obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, agents, params.barrierGain, params.barrierExponent, params.minAlt, params.timestep, params.maxIter, obstacles, tc.makePlots, tc.makeVideo, logical(params.useDoubleIntegrator), params.dampingCoeff, logical(params.useFixedTopology));
|
||||||
|
|
||||||
% Save simulation parameters to output file
|
% Save simulation parameters to output file
|
||||||
tc.testClass.writeInits();
|
tc.testClass.writeInits();
|
||||||
|
|
||||||
% Run
|
% Run
|
||||||
tc.testClass = tc.testClass.run();
|
tc.testClass = tc.testClass.run();
|
||||||
|
|
||||||
|
% Save results and clean up
|
||||||
|
tc.testClass = tc.testClass.teardown();
|
||||||
end
|
end
|
||||||
function csv_parametric_tests_random_agents(tc)
|
function csv_parametric_tests_random_agents(tc)
|
||||||
% Read in parameters to iterate over
|
% Read in parameters to iterate over
|
||||||
|
|||||||
@@ -33,6 +33,8 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
initialStepSize = 0.2; % gradient ascent step size at the first iteration. Decreases linearly to 0 based on maxIter.
|
initialStepSize = 0.2; % gradient ascent step size at the first iteration. Decreases linearly to 0 based on maxIter.
|
||||||
minAgents = 3; % Minimum number of agents to be randomly generated
|
minAgents = 3; % Minimum number of agents to be randomly generated
|
||||||
maxAgents = 4; % Maximum number of agents to be randomly generated
|
maxAgents = 4; % Maximum number of agents to be randomly generated
|
||||||
|
useDoubleIntegrator = false;
|
||||||
|
dampingCoeff = 2;
|
||||||
agents = cell(0, 1);
|
agents = cell(0, 1);
|
||||||
|
|
||||||
% Collision
|
% Collision
|
||||||
@@ -52,6 +54,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
sensor = sigmoidSensor;
|
sensor = sigmoidSensor;
|
||||||
|
|
||||||
% Communications
|
% Communications
|
||||||
|
useFixedTopology = false;
|
||||||
minCommsRange = 3; % Minimum randomly generated collision geometry size
|
minCommsRange = 3; % Minimum randomly generated collision geometry size
|
||||||
maxCommsRange = 5; % Maximum randomly generated collision geometry size
|
maxCommsRange = 5; % Maximum randomly generated collision geometry size
|
||||||
commsRanges = NaN;
|
commsRanges = NaN;
|
||||||
@@ -224,7 +227,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
end
|
end
|
||||||
|
|
||||||
% Initialize the simulation
|
% Initialize the simulation
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
end
|
end
|
||||||
function miSim_run(tc)
|
function miSim_run(tc)
|
||||||
% randomly create obstacles
|
% randomly create obstacles
|
||||||
@@ -363,7 +366,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
end
|
end
|
||||||
|
|
||||||
% Initialize the simulation
|
% Initialize the simulation
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
|
|
||||||
% Write out initialization state
|
% Write out initialization state
|
||||||
tc.testClass.writeInits();
|
tc.testClass.writeInits();
|
||||||
@@ -397,7 +400,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
tc.obstacles = cell(0, 1);
|
tc.obstacles = cell(0, 1);
|
||||||
tc.makePlots = false;
|
tc.makePlots = false;
|
||||||
tc.makeVideo = false;
|
tc.makeVideo = false;
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
|
|
||||||
centerIdx = floor(size(tc.testClass.partitioning, 1) / 2);
|
centerIdx = floor(size(tc.testClass.partitioning, 1) / 2);
|
||||||
tc.verifyEqual(tc.testClass.partitioning(centerIdx, centerIdx:(centerIdx + 2)), [2, 3, 1]); % all three near center
|
tc.verifyEqual(tc.testClass.partitioning(centerIdx, centerIdx:(centerIdx + 2)), [2, 3, 1]); % all three near center
|
||||||
@@ -422,7 +425,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
tc.obstacles = cell(0, 1);
|
tc.obstacles = cell(0, 1);
|
||||||
tc.makePlots = false;
|
tc.makePlots = false;
|
||||||
tc.makeVideo = false;
|
tc.makeVideo = false;
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
close(tc.testClass.fPerf);
|
close(tc.testClass.fPerf);
|
||||||
|
|
||||||
tc.verifyEqual(unique(tc.testClass.partitioning), [0; 1]);
|
tc.verifyEqual(unique(tc.testClass.partitioning), [0; 1]);
|
||||||
@@ -450,7 +453,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
|
|
||||||
% Initialize the simulation
|
% Initialize the simulation
|
||||||
tc.obstacles = cell(0, 1);
|
tc.obstacles = cell(0, 1);
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
|
|
||||||
% Run the simulation
|
% Run the simulation
|
||||||
tc.testClass = tc.testClass.run();end
|
tc.testClass = tc.testClass.run();end
|
||||||
@@ -485,7 +488,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
|
|
||||||
% Initialize the simulation
|
% Initialize the simulation
|
||||||
tc.obstacles = cell(0, 1);
|
tc.obstacles = cell(0, 1);
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
|
|
||||||
% Run the simulation
|
% Run the simulation
|
||||||
tc.testClass.run();
|
tc.testClass.run();
|
||||||
@@ -531,7 +534,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
tc.agents{2} = tc.agents{2}.initialize(tc.domain.center - d - [0, tc.collisionRanges(2) *1.1 + yOffset, 0], geometry2, tc.sensor, tc.commsRanges(2), tc.maxIter, tc.initialStepSize);
|
tc.agents{2} = tc.agents{2}.initialize(tc.domain.center - d - [0, tc.collisionRanges(2) *1.1 + yOffset, 0], geometry2, tc.sensor, tc.commsRanges(2), tc.maxIter, tc.initialStepSize);
|
||||||
|
|
||||||
% Initialize the simulation
|
% Initialize the simulation
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
|
|
||||||
% Run the simulation
|
% Run the simulation
|
||||||
tc.testClass.run();
|
tc.testClass.run();
|
||||||
@@ -571,7 +574,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
tc.agents{2} = tc.agents{2}.initialize(tc.domain.center - d, geometry2, tc.sensor, tc.commsRanges(2), tc.maxIter, tc.initialStepSize);
|
tc.agents{2} = tc.agents{2}.initialize(tc.domain.center - d, geometry2, tc.sensor, tc.commsRanges(2), tc.maxIter, tc.initialStepSize);
|
||||||
|
|
||||||
% Initialize the simulation
|
% Initialize the simulation
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
|
|
||||||
% Run the simulation
|
% Run the simulation
|
||||||
tc.testClass = tc.testClass.run();
|
tc.testClass = tc.testClass.run();
|
||||||
@@ -614,7 +617,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
tc.minAlt = 0;
|
tc.minAlt = 0;
|
||||||
tc.makePlots = false;
|
tc.makePlots = false;
|
||||||
tc.makeVideo = false;
|
tc.makeVideo = false;
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
|
|
||||||
% Communications link should be established
|
% Communications link should be established
|
||||||
tc.assertEqual(tc.testClass.adjacency, logical(true(2)));
|
tc.assertEqual(tc.testClass.adjacency, logical(true(2)));
|
||||||
@@ -659,7 +662,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
tc.minAlt = 0;
|
tc.minAlt = 0;
|
||||||
tc.makePlots = false;
|
tc.makePlots = false;
|
||||||
tc.makeVideo = false;
|
tc.makeVideo = false;
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
|
|
||||||
% Constraint adjacency matrix defined by LNA should be as follows
|
% Constraint adjacency matrix defined by LNA should be as follows
|
||||||
tc.assertEqual(tc.testClass.constraintAdjacencyMatrix, logical( ...
|
tc.assertEqual(tc.testClass.constraintAdjacencyMatrix, logical( ...
|
||||||
@@ -713,7 +716,7 @@ classdef test_miSim < matlab.unittest.TestCase
|
|||||||
tc.minAlt = 0;
|
tc.minAlt = 0;
|
||||||
tc.makePlots = false;
|
tc.makePlots = false;
|
||||||
tc.makeVideo = false;
|
tc.makeVideo = false;
|
||||||
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo);
|
tc.testClass = tc.testClass.initialize(tc.domain, tc.agents, tc.barrierGain, tc.barrierExponent, tc.minAlt, tc.timestep, tc.maxIter, tc.obstacles, tc.makePlots, tc.makeVideo, tc.useDoubleIntegrator, tc.dampingCoeff, tc.useFixedTopology);
|
||||||
|
|
||||||
% Constraint adjacency matrix defined by LNA should be as follows
|
% Constraint adjacency matrix defined by LNA should be as follows
|
||||||
tc.assertEqual(tc.testClass.constraintAdjacencyMatrix, logical( ...
|
tc.assertEqual(tc.testClass.constraintAdjacencyMatrix, logical( ...
|
||||||
|
|||||||
Reference in New Issue
Block a user