communications constraint improvements, experiment 1 design
This commit is contained in:
@@ -133,11 +133,22 @@ 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
|
||||||
|
|||||||
@@ -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
|
||||||
38
aerpaw/config/client3.yaml
Normal file
38
aerpaw/config/client3.yaml
Normal file
@@ -0,0 +1,38 @@
|
|||||||
|
# AERPAW UAV (Client) Configuration
|
||||||
|
|
||||||
|
# Unique 0-indexed UAV identifier (each UAV must have a distinct value)
|
||||||
|
uav_id: 2
|
||||||
|
|
||||||
|
# TDM (Time-Division Multiplexing) radio settings
|
||||||
|
# All UAVs share a common frequency; each transmits only during its time slot.
|
||||||
|
# Slot assignment uses wall-clock modular arithmetic (GPS/NTP synced).
|
||||||
|
tdm:
|
||||||
|
slot_duration: 0.5 # seconds per slot
|
||||||
|
guard_interval: 0.05 # seconds of silence at slot boundaries
|
||||||
|
|
||||||
|
# ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
|
||||||
|
origin:
|
||||||
|
lat: 35.72595214250436
|
||||||
|
lon: -78.69917609299937
|
||||||
|
alt: 0.0 # Alt=0 means ENU z directly becomes target altitude above home
|
||||||
|
# Environment-specific settings
|
||||||
|
environments:
|
||||||
|
local:
|
||||||
|
# MAVLink connection for SITL simulation (UDP)
|
||||||
|
mavlink:
|
||||||
|
ip: "127.0.0.1"
|
||||||
|
port: 14550
|
||||||
|
# Controller server address
|
||||||
|
controller:
|
||||||
|
ip: "127.0.0.1"
|
||||||
|
port: 5000
|
||||||
|
|
||||||
|
testbed:
|
||||||
|
# AERPAW testbed: E-VM listens, MAVLink Filter connects TO us (UDP)
|
||||||
|
mavlink:
|
||||||
|
ip: "192.168.32.26"
|
||||||
|
port: 14550
|
||||||
|
# Controller runs on host machine (192.168.109.1 from E-VM perspective)
|
||||||
|
controller:
|
||||||
|
ip: "192.168.109.1"
|
||||||
|
port: 5000
|
||||||
@@ -1,2 +1,2 @@
|
|||||||
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax
|
timestep, maxIter, minAlt, discretizationStep, protectedRange, initialStepSize, barrierGain, barrierExponent, collisionRadius, comRange, alphaDist, betaDist, alphaTilt, betaTilt, domainMin, domainMax, objectivePos, objectiveVar, sensorPerformanceMinimum, initialPositions, numObstacles, obstacleMin, obstacleMax
|
||||||
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, 150, 30.0, 0.1, 2.0, 3.0, 100, 3, "6.0, 6.0, 6.0", "20.0, 20.0, 20.0", "80.0, 80.0, 80.0", "0.25, 0.25, 0.25", "5.0, 5.0, 5.0", "0.1, 0.1, 0.1", "0.0, 0.0, 0.0", "80.0, 80.0, 80.0", "65.0, 65.0", "40, 25, 25, 40", 0.15, "15.0, 10.0, 40.0, 5.0, 10.0, 45.0, 27.5, 5.0, 45.0", 1, "1.0, 25.0, 0.0", "30.0, 30.0, 50.0"
|
||||||
|
@@ -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-11T11:45:17</Timestamp>
|
||||||
</MainBuildResult>
|
</MainBuildResult>
|
||||||
</coderapp.internal.mlc.mfz.MatlabCoderProjectState>
|
</coderapp.internal.mlc.mfz.MatlabCoderProjectState>
|
||||||
</MF0>
|
</MF0>
|
||||||
|
|||||||
@@ -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"
|
||||||
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
|
||||||
Reference in New Issue
Block a user