refactor experiment config

This commit is contained in:
2026-02-01 11:08:04 -08:00
parent ee238f239d
commit 1475d9e7d1
12 changed files with 180 additions and 97 deletions

View File

@@ -22,40 +22,41 @@ Protocol:
""" """
from pathlib import Path from pathlib import Path
import asyncio import asyncio
import os
import socket import socket
import yaml
from aerpawlib.runner import BasicRunner, entrypoint from aerpawlib.runner import BasicRunner, entrypoint
from aerpawlib.util import Coordinate, VectorNED from aerpawlib.util import Coordinate, VectorNED
from aerpawlib.vehicle import Drone from aerpawlib.vehicle import Drone
AERPAW_DIR = Path(__file__).parent.parent AERPAW_DIR = Path(__file__).parent.parent
CONFIG_DIR = AERPAW_DIR / "config" CONFIG_FILE = AERPAW_DIR / "config" / "config.yaml"
def load_origin(path: Path): def load_config():
"""Load ENU origin from config file. Returns (lat, lon, alt).""" """Load configuration from YAML file."""
with open(path, 'r') as f: with open(CONFIG_FILE, 'r') as f:
for line in f: return yaml.safe_load(f)
line = line.strip()
if not line or line.startswith('#'):
continue
parts = line.split(',')
if len(parts) == 3:
return float(parts[0]), float(parts[1]), float(parts[2])
raise ValueError(f"No valid origin found in {path}")
def load_server(path: Path): def detect_environment():
"""Load server address from config file. Returns (ip, port).""" """Detect whether we're on the AERPAW testbed or running locally."""
with open(path, 'r') as f: # Check for AERPAW_ENV environment variable first
for line in f: env = os.environ.get('AERPAW_ENV')
line = line.strip() if env in ('local', 'testbed'):
if not line or line.startswith('#'): return env
continue
parts = line.split(',') # Auto-detect based on network (testbed uses 192.168.122.x)
if len(parts) == 2: import subprocess
return parts[0].strip(), int(parts[1].strip()) try:
raise ValueError(f"No valid server address found in {path}") result = subprocess.run(['ip', 'addr'], capture_output=True, text=True, timeout=5)
if '192.168.122' in result.stdout:
return 'testbed'
except Exception:
pass
return 'local'
def parse_target(message: str): def parse_target(message: str):
@@ -71,26 +72,21 @@ def parse_target(message: str):
class UAVRunner(BasicRunner): class UAVRunner(BasicRunner):
def initialize_args(self, extra_args): def initialize_args(self, extra_args):
"""Load configuration from config files.""" """Load configuration from YAML config file."""
config = load_config()
env = detect_environment()
print(f"[UAV] Environment: {env}")
# Load origin # Load origin
origin_lat, origin_lon, origin_alt = load_origin(CONFIG_DIR / "origin.txt") origin = config['origin']
self.origin = Coordinate(origin_lat, origin_lon, origin_alt) self.origin = Coordinate(origin['lat'], origin['lon'], origin['alt'])
print(f"[UAV] Origin: {origin_lat}, {origin_lon}, {origin_alt}") print(f"[UAV] Origin: {origin['lat']}, {origin['lon']}, {origin['alt']}")
# Load server address - try testbed first, fall back to local # Load controller address for this environment
testbed_path = CONFIG_DIR / "server_testbed.txt" env_config = config['environments'][env]
local_path = CONFIG_DIR / "server.txt" self.server_ip = env_config['controller']['ip']
self.server_port = env_config['controller']['port']
if testbed_path.exists(): print(f"[UAV] Controller: {self.server_ip}:{self.server_port}")
try:
self.server_ip, self.server_port = load_server(testbed_path)
print(f"[UAV] Loaded testbed server config: {self.server_ip}:{self.server_port}")
except ValueError:
self.server_ip, self.server_port = load_server(local_path)
print(f"[UAV] Loaded local server config: {self.server_ip}:{self.server_port}")
else:
self.server_ip, self.server_port = load_server(local_path)
print(f"[UAV] Loaded local server config: {self.server_ip}:{self.server_port}")
@entrypoint @entrypoint
async def run_mission(self, drone: Drone): async def run_mission(self, drone: Drone):

36
aerpaw/config/config.yaml Normal file
View File

@@ -0,0 +1,36 @@
# AERPAW UAV Guidance System Configuration
# This file contains all settings for both simulation and testbed environments
# ENU coordinate system origin (AERPAW Lake Wheeler Road Field)
origin:
lat: 35.727436
lon: -78.696471
alt: 0.0 # Alt=0 means ENU z directly becomes target altitude above home
# Target positions in ENU coordinates (meters)
# Each target is assigned to a client in order: client 1 gets targets[0], etc.
targets:
- [10.5, 20.3, 45.0] # Client 1: east, north, up
- [25.0, 30.0, 30.0] # Client 2: east, north, up
# 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.122.1 from E-VM perspective)
controller:
ip: "192.168.122.1"
port: 5000

View File

@@ -1,7 +0,0 @@
# Drone connection string for aerpawlib/dronekit
# Examples:
# tcp:127.0.0.1:5760 - SITL TCP
# udp:127.0.0.1:14550 - SITL UDP (default MAVProxy output)
# /dev/ttyUSB0 - Serial connection
# /dev/ttyACM0 - Serial connection (Pixhawk USB)
udp:127.0.0.1:14550

View File

@@ -1,2 +0,0 @@
# AERPAW testbed - connect to MAVLink filter on E-VM
192.168.32.26:14550

View File

@@ -1,4 +0,0 @@
# Origin for ENU coordinate system (AERPAW Lake Wheeler Road Field)
# Format: lat,lon,alt (degrees, degrees, meters)
# Alt=0 means ENU z directly becomes the target altitude above home
35.727436,-78.696471,0.0

View File

@@ -1,3 +0,0 @@
# Local/fallback controller server address
# Format: ip,port
127.0.0.1,5000

View File

@@ -1,3 +0,0 @@
# AERPAW testbed controller server address
# Format: ip,port
192.168.122.1,5000

View File

@@ -1,2 +0,0 @@
10.5,20.3,45.0
25.0,30.0,30.0

View File

@@ -3,7 +3,7 @@ arguments (Input)
numClients (1, 1) int32; numClients (1, 1) int32;
end end
coder.extrinsic('disp', 'readmatrix'); coder.extrinsic('disp', 'loadTargetsFromYaml');
% Maximum clients supported % Maximum clients supported
MAX_CLIENTS = 4; MAX_CLIENTS = 4;
@@ -11,17 +11,17 @@ MAX_CLIENTS = 4;
% Allocate targets array (MAX_CLIENTS x 3) % Allocate targets array (MAX_CLIENTS x 3)
targets = zeros(MAX_CLIENTS, 3); targets = zeros(MAX_CLIENTS, 3);
% Load targets from file % Load targets from YAML config file
if coder.target('MATLAB') if coder.target('MATLAB')
disp('Loading targets from file (simulation)...'); disp('Loading targets from config.yaml (simulation)...');
targetsLoaded = readmatrix('aerpaw/config/targets.txt'); targetsLoaded = loadTargetsFromYaml('aerpaw/config/config.yaml');
numTargets = min(size(targetsLoaded, 1), numClients); numTargets = min(size(targetsLoaded, 1), numClients);
targets(1:numTargets, :) = targetsLoaded(1:numTargets, :); targets(1:numTargets, :) = targetsLoaded(1:numTargets, :);
disp(['Loaded ', num2str(numTargets), ' targets']); disp(['Loaded ', num2str(numTargets), ' targets']);
else else
coder.cinclude('controller_impl.h'); coder.cinclude('controller_impl.h');
% Define filename as null-terminated character array for C compatibility % Define filename as null-terminated character array for C compatibility
filename = ['config/targets.txt', char(0)]; filename = ['config/config.yaml', char(0)];
% loadTargets fills targets array (column-major for MATLAB compatibility) % loadTargets fills targets array (column-major for MATLAB compatibility)
coder.ceval('loadTargets', coder.ref(filename), ... coder.ceval('loadTargets', coder.ref(filename), ...
coder.ref(targets), int32(MAX_CLIENTS)); coder.ref(targets), int32(MAX_CLIENTS));

View File

@@ -82,23 +82,48 @@ void closeServer() {
int loadTargets(const char* filename, double* targets, int maxClients) { int loadTargets(const char* filename, double* targets, int maxClients) {
FILE* file = fopen(filename, "r"); FILE* file = fopen(filename, "r");
if (!file) { if (!file) {
std::cerr << "Failed to open targets file: " << filename << "\n"; std::cerr << "Failed to open config file: " << filename << "\n";
return 0; return 0;
} }
int count = 0; int count = 0;
char line[256];
bool inTargets = false;
// Simple YAML parser for targets section
// Expects format:
// targets:
// - [x, y, z]
// - [x, y, z]
while (fgets(line, sizeof(line), file) && count < maxClients) {
// Check if we've entered the targets section
if (strstr(line, "targets:") != nullptr) {
inTargets = true;
continue;
}
// If we hit another top-level key (no leading whitespace), exit targets section
if (inTargets && line[0] != ' ' && line[0] != '\t' && line[0] != '\n' && line[0] != '#') {
break;
}
// Parse target entries: " - [x, y, z]"
if (inTargets) {
double x, y, z; double x, y, z;
// Try to match the array format
if (sscanf(line, " - [%lf, %lf, %lf]", &x, &y, &z) == 3) {
// MATLAB uses column-major order, so for a maxClients x 3 matrix: // MATLAB uses column-major order, so for a maxClients x 3 matrix:
// Column 1 (x): indices 0, 1, 2, ... // Column 1 (x): indices 0, 1, 2, ...
// Column 2 (y): indices maxClients, maxClients+1, ... // Column 2 (y): indices maxClients, maxClients+1, ...
// Column 3 (z): indices 2*maxClients, 2*maxClients+1, ... // Column 3 (z): indices 2*maxClients, 2*maxClients+1, ...
while (count < maxClients && fscanf(file, "%lf,%lf,%lf", &x, &y, &z) == 3) { targets[count + 0 * maxClients] = x;
targets[count + 0 * maxClients] = x; // Column 1 targets[count + 1 * maxClients] = y;
targets[count + 1 * maxClients] = y; // Column 2 targets[count + 2 * maxClients] = z;
targets[count + 2 * maxClients] = z; // Column 3
std::cout << "Loaded target " << (count + 1) << ": " << x << "," << y << "," << z << "\n"; std::cout << "Loaded target " << (count + 1) << ": " << x << "," << y << "," << z << "\n";
count++; count++;
} }
}
}
fclose(file); fclose(file);
return count; return count;

View File

@@ -0,0 +1,42 @@
function targets = loadTargetsFromYaml(filename)
%LOADTARGETSFROMYAML Load target coordinates from YAML config file
% targets = loadTargetsFromYaml(filename) reads the targets section
% from a YAML config file and returns an Nx3 matrix of [x, y, z] coordinates.
targets = [];
fid = fopen(filename, 'r');
if fid == -1
error('Could not open file: %s', filename);
end
inTargets = false;
while ~feof(fid)
line = fgetl(fid);
if ~ischar(line)
break;
end
% Check if we've entered the targets section
if contains(line, 'targets:')
inTargets = true;
continue;
end
% If we hit another top-level key, exit targets section
if inTargets && ~isempty(line) && line(1) ~= ' ' && line(1) ~= '#'
break;
end
% Parse target entries: " - [x, y, z]"
if inTargets
% Extract numbers from array format
match = regexp(line, '\[\s*([-\d.]+)\s*,\s*([-\d.]+)\s*,\s*([-\d.]+)\s*\]', 'tokens');
if ~isempty(match)
coords = str2double(match{1});
targets = [targets; coords]; %#ok<AGROW>
end
end
end
fclose(fid);
end

View File

@@ -17,39 +17,44 @@ if [ -d "venv" ]; then
source venv/bin/activate source venv/bin/activate
fi fi
# Connection strings
# AERPAW testbed: E-VM LISTENS on port 14550, MAVLink Filter connects TO us
# See: https://sites.google.com/ncsu.edu/aerpaw-user-manual/6-sample-experiments-repository/6-2-vehicle-control-software/vcs1-preplanned-trajectory
# "the IP address corresponds to the E-VM IP address and the port is where
# the MAVLink filter expects to find the vehicle control script"
TESTBED_CONN="udp:0.0.0.0:14550"
LOCAL_CONN="udp:127.0.0.1:14550"
# Function to check if we're in testbed environment # Function to check if we're in testbed environment
check_testbed() { check_testbed() {
# Check if we're on the AERPAW testbed network (192.168.122.X)
ip addr | grep -q "192.168.122" ip addr | grep -q "192.168.122"
return $? return $?
} }
# Determine connection based on argument or auto-detection # Determine environment based on argument or auto-detection
if [ "$1" = "testbed" ]; then if [ "$1" = "testbed" ]; then
CONN="$TESTBED_CONN" ENV="testbed"
echo "[run_uav] Forced testbed mode: $CONN" echo "[run_uav] Forced testbed mode"
elif [ "$1" = "local" ]; then elif [ "$1" = "local" ]; then
CONN="$LOCAL_CONN" ENV="local"
echo "[run_uav] Forced local mode: $CONN" echo "[run_uav] Forced local mode"
else else
echo "[run_uav] Auto-detecting environment..." echo "[run_uav] Auto-detecting environment..."
if check_testbed; then if check_testbed; then
CONN="$TESTBED_CONN" ENV="testbed"
echo "[run_uav] Testbed detected, using: $CONN" echo "[run_uav] Testbed detected"
else else
CONN="$LOCAL_CONN" ENV="local"
echo "[run_uav] Local mode (testbed not reachable), using: $CONN" echo "[run_uav] Local mode"
fi fi
fi fi
# Export environment for Python to use
export AERPAW_ENV="$ENV"
# Read MAVLink connection from config.yaml using Python
CONN=$(python3 -c "
import yaml
with open('config/config.yaml') as f:
cfg = yaml.safe_load(f)
env = cfg['environments']['$ENV']['mavlink']
print(f\"udp:{env['ip']}:{env['port']}\")
")
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 -m aerpawlib \