diff --git a/config/system_config.json b/config/system_config.json index ace68d7..e2ec469 100644 --- a/config/system_config.json +++ b/config/system_config.json @@ -24,17 +24,50 @@ ] }, "data_source": { - "host": "localhost", - "port": 8081, - "username": "dianxin", - "password": "dianxin@123", - "auth_path": "/login", - "aircraft_path": "/openApi/getCurrentFlightPositions", - "vehicle_path": "/openApi/getCurrentVehiclePositions", - "traffic_light_path": "/getTrafficLightSignals", - "refresh_interval_ms": 1000, - "timeout_ms": 5000, - "read_timeout_ms": 2000 + "position": { + "host": "localhost", + "port": 8081, + "aircraft_path": "/openApi/getCurrentFlightPositions", + "vehicle_path": "/openApi/getCurrentVehiclePositions", + "refresh_interval_ms": 1000, + "auth": { + "username": "dianxin", + "password": "dianxin@123", + "auth_path": "/login", + "auth_required": true + }, + "timeout_ms": 5000, + "read_timeout_ms": 2000 + }, + "unmanned_vehicle": { + "host": "localhost", + "port": 8081, + "status_path": "/openApi/getVehicleStatus", + "command_path": "/openApi/sendVehicleCommand", + "refresh_interval_ms": 1000, + "auth": { + "username": "dianxin", + "password": "dianxin@123", + "auth_path": "/login", + "auth_required": false + }, + "timeout_ms": 5000, + "read_timeout_ms": 2000 + }, + "traffic_light": { + "host": "localhost", + "port": 8081, + "signal_path": "/openApi/getTrafficLightSignals", + "refresh_interval_ms": 1000, + "auth": { + "username": "dianxin", + "password": "dianxin@123", + "auth_path": "/login", + "auth_required": false + }, + "timeout_ms": 5000, + "read_timeout_ms": 2000 + } }, "warning": { "warning_interval_ms": 1000, @@ -60,7 +93,7 @@ } }, "logging": { - "level": "info", + "level": "debug", "file": "logs/system.log", "max_size_mb": 10, "max_files": 5, diff --git a/docs/requirements.md b/docs/requirements.md new file mode 100644 index 0000000..8e26ff8 --- /dev/null +++ b/docs/requirements.md @@ -0,0 +1,47 @@ +# 需求文档 + +## 1. 需求概述 + +## 2. 功能需求 + +### 2.1 航空器、车辆位置显示 + +### 2.2 冲突检测 + +### 2.3 红绿灯信号处理 + +### 2.4 数据采集 + +1. 航空器和车辆位置数据 + 1. 数据来源: + 1. 航空器:ADS-B + 2. 车辆:1.8G北斗 + 2. 数据格式: + 参考 official_api.md + 3. 采集频率: + 1. 航空器:3Hz + 2. 车辆:3Hz +2. 红绿灯信号 + 1. 数据来源: + 1. 红绿灯:5G + 2. 数据格式: + 参考 official_api.md + 3. 采集频率: + 1. 红绿灯:1Hz +3. 无人车状态 + 1. 数据来源: + 1. 无人车:5G + 2. 数据格式: + 参考 official_api.md + 3. 采集频率: + 1. 无人车:1Hz + +### 2.5 数据处理 + +### 2.6 数据存储 + +## 3. 非功能需求 + +## 4. 约束 + +## 5. 其他 diff --git a/src/collector/DataCollector.cpp b/src/collector/DataCollector.cpp index f21b081..569d14c 100644 --- a/src/collector/DataCollector.cpp +++ b/src/collector/DataCollector.cpp @@ -3,9 +3,13 @@ #include "utils/Logger.h" #include #include +#include +#include DataCollector::DataCollector() - : lastSuccessfulFetch_(std::chrono::steady_clock::now()) // 初始化时间戳 + : last_position_fetch_(std::chrono::steady_clock::now()) + , last_unmanned_fetch_(std::chrono::steady_clock::now()) + , last_traffic_light_fetch_(std::chrono::steady_clock::now()) , last_warning_time_(std::chrono::steady_clock::now()) { } @@ -18,7 +22,9 @@ bool DataCollector::initialize(const DataSourceConfig& dataSourceConfig, const W dataSourceConfig_ = dataSourceConfig; dataSource_ = std::make_shared(dataSourceConfig_); warnConfig_ = warnConfig; - lastSuccessfulFetch_ = std::chrono::steady_clock::now(); // 重置时间戳 + last_position_fetch_ = std::chrono::steady_clock::now(); + last_unmanned_fetch_ = std::chrono::steady_clock::now(); + last_traffic_light_fetch_ = std::chrono::steady_clock::now(); last_warning_time_ = std::chrono::steady_clock::now(); } return true; @@ -35,8 +41,9 @@ void DataCollector::start() { } running_ = true; - lastSuccessfulFetch_ = std::chrono::steady_clock::now(); // 记录启动时间 - last_warning_time_ = lastSuccessfulFetch_; // 初始化告警时间 + last_position_fetch_ = std::chrono::steady_clock::now(); + last_unmanned_fetch_ = std::chrono::steady_clock::now(); + last_traffic_light_fetch_ = std::chrono::steady_clock::now(); // 尝试连接,但即使失败也继续运行 if (!dataSource_->connect()) { @@ -45,7 +52,10 @@ void DataCollector::start() { checkTimeout(); } - collectorThread_ = std::thread(&DataCollector::collectLoop, this); + // 启动三个独立的采集线程 + positionThread_ = std::thread(&DataCollector::positionLoop, this); + unmannedThread_ = std::thread(&DataCollector::unmannedLoop, this); + trafficLightThread_ = std::thread(&DataCollector::trafficLightLoop, this); } void DataCollector::stop() { @@ -54,8 +64,16 @@ void DataCollector::stop() { } running_ = false; - if (collectorThread_.joinable()) { - collectorThread_.join(); + + // 等待所有线程结束 + if (positionThread_.joinable()) { + positionThread_.join(); + } + if (unmannedThread_.joinable()) { + unmannedThread_.join(); + } + if (trafficLightThread_.joinable()) { + trafficLightThread_.join(); } if (dataSource_) { @@ -63,37 +81,85 @@ void DataCollector::stop() { } } -void DataCollector::collectLoop() { - Logger::debug("数据采集循环启动,刷新间隔: ", dataSourceConfig_.refresh_interval_ms, "ms"); +void DataCollector::positionLoop() { + Logger::debug("位置数据采集循环启动,刷新间隔: ", dataSourceConfig_.position.refresh_interval_ms, "ms"); auto next_collection_time = std::chrono::steady_clock::now(); while (running_) { - loopCount_++; - Logger::debug("开始第 ", loopCount_.load(), " 次数据采集循环"); - - bool success = fetchData(); + bool success = fetchPositionData(); if (!success) { - Logger::warning("第 ", loopCount_.load(), " 次数据采集失败"); - checkTimeout(); // 每次获取失败都检查超时 + Logger::warning("位置数据采集失败"); + checkTimeout(); } - // 即使成功获取数据,也定期检查超时状态 - checkTimeout(); - // 计算下一次采集时间 - next_collection_time += std::chrono::milliseconds(dataSourceConfig_.refresh_interval_ms); + next_collection_time += std::chrono::milliseconds(dataSourceConfig_.position.refresh_interval_ms); + auto now = std::chrono::steady_clock::now(); + + if (next_collection_time > now) { + auto wait_time = std::chrono::duration_cast( + next_collection_time - now).count(); + if (wait_time > 0) { + std::this_thread::sleep_for(std::chrono::milliseconds(wait_time)); + } + } else { + // 如果已经超过了下一次采集时间,立即重置 + next_collection_time = std::chrono::steady_clock::now(); + } + } +} + +void DataCollector::unmannedLoop() { + Logger::debug("无人车状态采集循环启动,刷新间隔: ", dataSourceConfig_.vehicle.refresh_interval_ms, "ms"); + auto next_collection_time = std::chrono::steady_clock::now(); + + while (running_) { + bool success = fetchUnmannedVehicleData(); + if (!success) { + Logger::warning("无人车状态采集失败"); + checkTimeout(); + } + + // 计算下一次采集时间 + next_collection_time += std::chrono::milliseconds(dataSourceConfig_.vehicle.refresh_interval_ms); + auto now = std::chrono::steady_clock::now(); + + if (next_collection_time > now) { + auto wait_time = std::chrono::duration_cast( + next_collection_time - now).count(); + if (wait_time > 0) { + std::this_thread::sleep_for(std::chrono::milliseconds(wait_time)); + } + } else { + // 如果已经超过了下一次采集时间,立即重置 + next_collection_time = std::chrono::steady_clock::now(); + } + } +} + +void DataCollector::trafficLightLoop() { + Logger::debug("红绿灯数据采集循环启动,刷新间隔: ", dataSourceConfig_.traffic_light.refresh_interval_ms, "ms"); + auto next_collection_time = std::chrono::steady_clock::now(); + + while (running_) { + bool success = fetchTrafficLightData(); + if (!success) { + Logger::warning("红绿灯数据采集失败"); + checkTimeout(); + } + + // 计算下一次采集时间 + next_collection_time += std::chrono::milliseconds(dataSourceConfig_.traffic_light.refresh_interval_ms); auto now = std::chrono::steady_clock::now(); if (next_collection_time > now) { auto wait_time = std::chrono::duration_cast( next_collection_time - now).count(); if (wait_time > 0) { - Logger::debug("等待 ", wait_time, "ms 进行下一次采集"); std::this_thread::sleep_for(std::chrono::milliseconds(wait_time)); } } else { // 如果已经超过了下一次采集时间,立即重置 - Logger::warning("数据采集延迟,重置采集时间"); next_collection_time = std::chrono::steady_clock::now(); } } @@ -101,124 +167,158 @@ void DataCollector::collectLoop() { void DataCollector::checkTimeout() { auto now = std::chrono::steady_clock::now(); - auto elapsed = std::chrono::duration_cast( - now - lastSuccessfulFetch_).count(); - - // 检查是否达到告警间隔 + + // 检查位置数据超时 + auto position_elapsed = std::chrono::duration_cast( + now - last_position_fetch_).count(); + if (position_elapsed > dataSourceConfig_.position.timeout_ms) { + sendTimeoutWarning("position", position_elapsed); + } + + // 检查无人车数据超时 + auto unmanned_elapsed = std::chrono::duration_cast( + now - last_unmanned_fetch_).count(); + if (unmanned_elapsed > dataSourceConfig_.vehicle.timeout_ms) { + sendTimeoutWarning("unmanned", unmanned_elapsed); + } + + // 检查红绿灯数据超时 + auto traffic_light_elapsed = std::chrono::duration_cast( + now - last_traffic_light_fetch_).count(); + if (traffic_light_elapsed > dataSourceConfig_.traffic_light.timeout_ms) { + sendTimeoutWarning("traffic_light", traffic_light_elapsed); + } +} + +void DataCollector::resetTimeout(const std::string& source) { + auto now = std::chrono::steady_clock::now(); + + if (source == "position") { + auto elapsed = std::chrono::duration_cast( + now - last_position_fetch_).count(); + if (elapsed > dataSourceConfig_.position.timeout_ms) { + Logger::info("Position data source connection restored after ", elapsed, "ms timeout"); + } + last_position_fetch_ = now; + } + else if (source == "unmanned") { + auto elapsed = std::chrono::duration_cast( + now - last_unmanned_fetch_).count(); + if (elapsed > dataSourceConfig_.vehicle.timeout_ms) { + Logger::info("Unmanned vehicle data source connection restored after ", elapsed, "ms timeout"); + } + last_unmanned_fetch_ = now; + } + else if (source == "traffic_light") { + auto elapsed = std::chrono::duration_cast( + now - last_traffic_light_fetch_).count(); + if (elapsed > dataSourceConfig_.traffic_light.timeout_ms) { + Logger::info("Traffic light data source connection restored after ", elapsed, "ms timeout"); + } + last_traffic_light_fetch_ = now; + } +} + +void DataCollector::sendTimeoutWarning(const std::string& source, int64_t elapsed_ms) { + auto now = std::chrono::steady_clock::now(); auto warning_elapsed = std::chrono::duration_cast( now - last_warning_time_).count(); if (warning_elapsed >= warnConfig_.warning_interval_ms) { - // 如果超过了超时阈值,发送警告 - if (elapsed > dataSourceConfig_.read_timeout_ms) { - sendTimeoutWarning(elapsed); - last_warning_time_ = now; - - // 只在非测试环境中记录警告日志 - if (system_) { - Logger::warning("Data source timeout: No response for ", elapsed, "ms"); - } else { - Logger::debug("Data source timeout in test environment: ", elapsed, "ms"); - } + if (!system_) { + Logger::debug("System not set, skipping timeout warning"); + return; } - } -} -void DataCollector::resetTimeout() { - auto now = std::chrono::steady_clock::now(); - auto elapsed = std::chrono::duration_cast( - now - lastSuccessfulFetch_).count(); + network::TimeoutWarningMessage msg; + msg.source = source; + msg.elapsed_ms = elapsed_ms; - if (elapsed > dataSourceConfig_.timeout_ms) { - // 如果之前处于超时状态,记录恢复日志 - Logger::info("Data source connection restored after ", elapsed, "ms timeout"); + // 根据数据源类型设置超时阈值 + int64_t timeout_ms = 0; + if (source == "position") { + timeout_ms = dataSourceConfig_.position.timeout_ms; + } + else if (source == "unmanned") { + timeout_ms = dataSourceConfig_.vehicle.timeout_ms; + } + else if (source == "traffic_light") { + timeout_ms = dataSourceConfig_.traffic_light.timeout_ms; + } + + msg.is_read_timeout = (elapsed_ms > timeout_ms); + + system_->broadcastTimeoutWarning(msg); + last_warning_time_ = now; + + Logger::debug("Sent timeout warning: source=", msg.source, + " elapsed=", msg.elapsed_ms, "ms", + " is_read_timeout=", msg.is_read_timeout ? "true" : "false", + " timeout=", timeout_ms); } - - lastSuccessfulFetch_ = now; } -void DataCollector::sendTimeoutWarning(int64_t elapsed_ms) { - if (!system_) { - Logger::debug("System not set, skipping timeout warning"); - return; - } - - network::TimeoutWarningMessage msg; - msg.source = "data_source"; - msg.elapsed_ms = elapsed_ms; - // 如果超时时间超过了读取超时阈值,就是读取超时 - msg.is_read_timeout = (elapsed_ms > dataSourceConfig_.read_timeout_ms); - - system_->broadcastTimeoutWarning(msg); - Logger::debug("Sent timeout warning: source=", msg.source, - " elapsed=", msg.elapsed_ms, "ms", - " is_read_timeout=", msg.is_read_timeout ? "true" : "false", - " read_timeout=", dataSourceConfig_.read_timeout_ms, - " connect_timeout=", dataSourceConfig_.timeout_ms); -} - -bool DataCollector::fetchData() { - bool success = true; +bool DataCollector::fetchPositionData() { std::vector newAircraft; std::vector newVehicles; - std::vector newSignals; - Logger::debug("开始获取数据..."); - - if (dataSource_->fetchAircraftData(newAircraft)) { - std::lock_guard lock(cacheMutex_); - // 更新时间戳为数据源中最新的时间戳 - int64_t maxTimestamp = 0; - for (const auto& aircraft : newAircraft) { - if (aircraft.timestamp > maxTimestamp) { - maxTimestamp = aircraft.timestamp; - } - } - if (maxTimestamp > 0) { - lastAircraftTimestamp_.store(maxTimestamp); - Logger::debug("更新航空器时间戳为: ", lastAircraftTimestamp_.load()); - } - aircraftCache_ = std::move(newAircraft); - Logger::debug("成功获取航空器数据: ", aircraftCache_.size(), " 架"); - } else { - Logger::warning("获取航空器数据失败"); - success = false; + if (!dataSource_) { + Logger::error("No data source available"); + return false; } - if (dataSource_->fetchVehicleData(newVehicles)) { - std::lock_guard lock(cacheMutex_); - // 更新时间戳为数据源中最新的时间戳 - int64_t maxTimestamp = 0; - for (const auto& vehicle : newVehicles) { - if (vehicle.timestamp > maxTimestamp) { - maxTimestamp = vehicle.timestamp; - } - } - if (maxTimestamp > 0) { - lastVehicleTimestamp_.store(maxTimestamp); - Logger::debug("更新车辆时间戳为: ", lastVehicleTimestamp_.load()); - } - vehicleCache_ = std::move(newVehicles); - Logger::debug("成功获取车辆数据: ", vehicleCache_.size(), " 辆"); - } else { - Logger::warning("获取车辆数据失败"); - success = false; - } - - if (dataSource_->fetchTrafficLightSignals(newSignals)) { - std::lock_guard lock(cacheMutex_); - trafficLightCache_ = std::move(newSignals); - Logger::debug("成功获取红绿灯数据: ", trafficLightCache_.size(), " 个"); - } else { - Logger::warning("获取红绿灯数据失败"); - success = false; - } + bool success = dataSource_->fetchPositionAircraftData(newAircraft) && + dataSource_->fetchPositionVehicleData(newVehicles); if (success) { - resetTimeout(); // 重置超时计时器 - Logger::debug("数据获取完成"); - } else { - Logger::warning("数据获取过程中存在错误"); + std::lock_guard lock(cacheMutex_); + aircraftCache_ = std::move(newAircraft); + vehicleCache_ = std::move(newVehicles); + resetTimeout("position"); + } + + return success; +} + +bool DataCollector::fetchUnmannedVehicleData() { + if (!dataSource_) { + Logger::error("数据源未初始化"); + return false; + } + + bool success = false; + auto& vehicles = ControllableVehicles::getInstance().getVehicles(); + for (const auto& vehicle : vehicles) { + if (vehicle.type == "UNMANNED") { + std::string status; + if (dataSource_->fetchUnmannedVehicleStatus(vehicle.vehicleNo, status)) { + success = true; + } else { + Logger::error("获取无人车状态失败, vehicleNo: " + vehicle.vehicleNo); + } + } + } + + if (success) { + resetTimeout("unmanned"); + } + return success; +} + +bool DataCollector::fetchTrafficLightData() { + std::vector newSignals; + + if (!dataSource_) { + Logger::error("No data source available"); + return false; + } + + bool success = dataSource_->fetchTrafficLightSignals(newSignals); + + if (success) { + std::lock_guard lock(cacheMutex_); + trafficLightCache_ = std::move(newSignals); + resetTimeout("traffic_light"); } return success; @@ -259,7 +359,7 @@ void DataCollector::refresh() { trafficLightCache_ = std::move(newSignals); } - if (dataSource_->fetchAircraftData(newAircraft)) { + if (dataSource_->fetchPositionAircraftData(newAircraft)) { std::lock_guard lock(cacheMutex_); // 更新运动信息 for (auto& a : newAircraft) { @@ -277,7 +377,7 @@ void DataCollector::refresh() { aircraftCache_ = std::move(newAircraft); } - if (dataSource_->fetchVehicleData(newVehicles)) { + if (dataSource_->fetchPositionVehicleData(newVehicles)) { std::lock_guard lock(cacheMutex_); // 更新运动信息 for (auto& v : newVehicles) { @@ -299,4 +399,12 @@ void DataCollector::refresh() { Logger::error("刷新数据失败: ", e.what()); throw; } +} + +bool DataCollector::fetchUnmannedVehicleStatus(const std::string& vehicle_id, std::string& status) { + if (!dataSource_) { + Logger::error("No data source available"); + return false; + } + return dataSource_->fetchUnmannedVehicleStatus(vehicle_id, status); } \ No newline at end of file diff --git a/src/collector/DataCollector.h b/src/collector/DataCollector.h index 51f7c2d..0650ddf 100644 --- a/src/collector/DataCollector.h +++ b/src/collector/DataCollector.h @@ -12,6 +12,7 @@ #include "types/BasicTypes.h" #include "config/WarnConfig.h" #include "types/TrafficLightTypes.h" +#include "vehicle/ControllableVehicles.h" // 前向声明 class System; @@ -34,6 +35,9 @@ public: std::vector getTrafficLightSignals(); bool fetchTrafficLightSignals(std::vector& signals); + // 无人车状态获取接口 + bool fetchUnmannedVehicleStatus(const std::string& vehicle_id, std::string& status); + // 添加设置数据源的方法(用于测试) void setDataSource(std::shared_ptr source) { dataSource_ = source; @@ -55,7 +59,11 @@ private: std::shared_ptr system_; DataSourceConfig dataSourceConfig_; WarnConfig warnConfig_; - std::thread collectorThread_; + + // 三个独立的采集线程 + std::thread positionThread_; // 位置数据采集线程 + std::thread unmannedThread_; // 无人车状态采集线程 + std::thread trafficLightThread_; // 红绿灯数据采集线程 std::atomic running_{false}; std::atomic loopCount_{0}; @@ -74,16 +82,24 @@ private: std::atomic lastVehicleTimestamp_{0}; // 超时检测相关 - std::chrono::steady_clock::time_point lastSuccessfulFetch_; + std::chrono::steady_clock::time_point last_position_fetch_; // 位置数据最后获取时间 + std::chrono::steady_clock::time_point last_unmanned_fetch_; // 无人车状态最后获取时间 + std::chrono::steady_clock::time_point last_traffic_light_fetch_; // 红绿灯数据最后获取时间 std::chrono::steady_clock::time_point last_warning_time_; std::chrono::steady_clock::time_point last_log_time_; void checkTimeout(); - void resetTimeout(); - void sendTimeoutWarning(int64_t elapsed_ms); + void resetTimeout(const std::string& source); // 修改resetTimeout方法签名 + void sendTimeoutWarning(const std::string& source, int64_t elapsed_ms); // 修改告警方法签名 - void collectLoop(); - bool fetchData(); + // 三个独立的采集循环 + void positionLoop(); // 位置数据采集循环 + void unmannedLoop(); // 无人车状态采集循环 + void trafficLightLoop(); // 红绿灯数据采集循环 + + bool fetchPositionData(); // 获取位置数据 + bool fetchUnmannedVehicleData(); // 获取无人车状态数据 + bool fetchTrafficLightData(); // 获取红绿灯数据 }; #endif // AIRPORT_COLLECTOR_DATA_COLLECTOR_H \ No newline at end of file diff --git a/src/collector/DataSource.h b/src/collector/DataSource.h index edc559a..a38b720 100644 --- a/src/collector/DataSource.h +++ b/src/collector/DataSource.h @@ -3,20 +3,35 @@ #include "types/BasicTypes.h" #include "types/TrafficLightTypes.h" +#include "types/VehicleCommand.h" #include #include +#include class DataSource { public: + // 数据源类型 + enum class DataSourceType { + POSITION, // 位置数据接口 + UNMANNED, // 无人车接口 + TRAFFIC_LIGHT // 红绿灯接口 + }; + virtual ~DataSource() = default; virtual bool connect() = 0; virtual void disconnect() = 0; virtual bool isAvailable() const = 0; - // 获取数据的接口 - virtual bool fetchAircraftData(std::vector& aircraft) = 0; - virtual bool fetchVehicleData(std::vector& vehicles) = 0; + // 位置数据接口 + virtual bool fetchPositionAircraftData(std::vector& aircraft) = 0; + virtual bool fetchPositionVehicleData(std::vector& vehicles) = 0; + + // 无人车接口 + virtual bool sendUnmannedVehicleCommand(const std::string& vehicle_id, const VehicleCommand& command) = 0; + virtual bool fetchUnmannedVehicleStatus(const std::string& vehicle_id, std::string& status) = 0; + + // 红绿灯接口 virtual bool fetchTrafficLightSignals(std::vector& signals) = 0; }; diff --git a/src/collector/DataSourceConfig.cpp b/src/collector/DataSourceConfig.cpp new file mode 100644 index 0000000..2f8829d --- /dev/null +++ b/src/collector/DataSourceConfig.cpp @@ -0,0 +1,47 @@ +#include "DataSourceConfig.h" +#include "config/SystemConfig.h" +#include "utils/Logger.h" + +DataSourceConfig DataSourceConfig::fromSystemConfig(const SystemConfig& config) { + DataSourceConfig dataSourceConfig; + + // 转换位置数据源配置 + dataSourceConfig.position.host = config.data_source.position.host; + dataSourceConfig.position.port = config.data_source.position.port; + dataSourceConfig.position.aircraft_path = config.data_source.position.aircraft_path; + dataSourceConfig.position.vehicle_path = config.data_source.position.vehicle_path; + dataSourceConfig.position.refresh_interval_ms = config.data_source.position.refresh_interval_ms; + dataSourceConfig.position.timeout_ms = config.data_source.position.timeout_ms; + dataSourceConfig.position.read_timeout_ms = config.data_source.position.read_timeout_ms; + dataSourceConfig.position.auth.username = config.data_source.position.auth.username; + dataSourceConfig.position.auth.password = config.data_source.position.auth.password; + dataSourceConfig.position.auth.auth_path = config.data_source.position.auth.auth_path; + dataSourceConfig.position.auth.auth_required = config.data_source.position.auth.auth_required; + + // 转换无人车数据源配置 + dataSourceConfig.vehicle.host = config.data_source.unmanned_vehicle.host; + dataSourceConfig.vehicle.port = config.data_source.unmanned_vehicle.port; + dataSourceConfig.vehicle.status_path = config.data_source.unmanned_vehicle.status_path; + dataSourceConfig.vehicle.command_path = config.data_source.unmanned_vehicle.command_path; + dataSourceConfig.vehicle.refresh_interval_ms = config.data_source.unmanned_vehicle.refresh_interval_ms; + dataSourceConfig.vehicle.timeout_ms = config.data_source.unmanned_vehicle.timeout_ms; + dataSourceConfig.vehicle.read_timeout_ms = config.data_source.unmanned_vehicle.read_timeout_ms; + dataSourceConfig.vehicle.auth.username = config.data_source.unmanned_vehicle.auth.username; + dataSourceConfig.vehicle.auth.password = config.data_source.unmanned_vehicle.auth.password; + dataSourceConfig.vehicle.auth.auth_path = config.data_source.unmanned_vehicle.auth.auth_path; + dataSourceConfig.vehicle.auth.auth_required = config.data_source.unmanned_vehicle.auth.auth_required; + + // 转换红绿灯数据源配置 + dataSourceConfig.traffic_light.host = config.data_source.traffic_light.host; + dataSourceConfig.traffic_light.port = config.data_source.traffic_light.port; + dataSourceConfig.traffic_light.signal_path = config.data_source.traffic_light.signal_path; + dataSourceConfig.traffic_light.refresh_interval_ms = config.data_source.traffic_light.refresh_interval_ms; + dataSourceConfig.traffic_light.timeout_ms = config.data_source.traffic_light.timeout_ms; + dataSourceConfig.traffic_light.read_timeout_ms = config.data_source.traffic_light.read_timeout_ms; + dataSourceConfig.traffic_light.auth.username = config.data_source.traffic_light.auth.username; + dataSourceConfig.traffic_light.auth.password = config.data_source.traffic_light.auth.password; + dataSourceConfig.traffic_light.auth.auth_path = config.data_source.traffic_light.auth.auth_path; + dataSourceConfig.traffic_light.auth.auth_required = config.data_source.traffic_light.auth.auth_required; + + return dataSourceConfig; +} \ No newline at end of file diff --git a/src/collector/DataSourceConfig.h b/src/collector/DataSourceConfig.h index e4f44a4..650fb34 100644 --- a/src/collector/DataSourceConfig.h +++ b/src/collector/DataSourceConfig.h @@ -2,19 +2,170 @@ #define AIRPORT_COLLECTOR_DATA_SOURCE_CONFIG_H #include +#include +#include -struct DataSourceConfig { - std::string host; - uint16_t port; - std::string aircraft_path; - std::string vehicle_path; - std::string traffic_light_path; - std::string auth_path; // 认证接口路径 - std::string username; // 用户名 - std::string password; // 密码 - int refresh_interval_ms; - int timeout_ms; // 连接超时时间, 单位: 毫秒 - int read_timeout_ms; // 读取超时时间, 单位: 毫秒, 小于连接超时时间 +using json = nlohmann::json; + +// 前向声明 +class SystemConfig; + +// 认证配置 +struct AuthConfig { + std::string username; // 认证用户名 + std::string password; // 认证密码 + std::string auth_path; // 认证接口路径 + bool auth_required = false; // 是否需要认证 }; +// AuthConfig 的 JSON 序列化/反序列化函数 +inline void to_json(json& j, const AuthConfig& a) { + j = json{ + {"username", a.username}, + {"password", a.password}, + {"auth_path", a.auth_path}, + {"auth_required", a.auth_required} + }; +} + +inline void from_json(const json& j, AuthConfig& a) { + j.at("username").get_to(a.username); + j.at("password").get_to(a.password); + j.at("auth_path").get_to(a.auth_path); + j.at("auth_required").get_to(a.auth_required); +} + +// 位置数据源配置 +struct PositionDataConfig { + std::string host; // 服务器地址 + int port; // 服务器端口 + std::string aircraft_path; // 航空器位置接口 + std::string vehicle_path; // 车辆位置接口 + int refresh_interval_ms; // 位置数据刷新间隔 + int timeout_ms; // 连接超时时间 + int read_timeout_ms; // 读取超时时间 + AuthConfig auth; // 认证配置 +}; + +// PositionDataConfig 的 JSON 序列化/反序列化函数 +inline void to_json(json& j, const PositionDataConfig& p) { + j = json{ + {"host", p.host}, + {"port", p.port}, + {"aircraft_path", p.aircraft_path}, + {"vehicle_path", p.vehicle_path}, + {"refresh_interval_ms", p.refresh_interval_ms}, + {"timeout_ms", p.timeout_ms}, + {"read_timeout_ms", p.read_timeout_ms}, + {"auth", p.auth} + }; +} + +inline void from_json(const json& j, PositionDataConfig& p) { + j.at("host").get_to(p.host); + j.at("port").get_to(p.port); + j.at("aircraft_path").get_to(p.aircraft_path); + j.at("vehicle_path").get_to(p.vehicle_path); + j.at("refresh_interval_ms").get_to(p.refresh_interval_ms); + j.at("timeout_ms").get_to(p.timeout_ms); + j.at("read_timeout_ms").get_to(p.read_timeout_ms); + j.at("auth").get_to(p.auth); +} + +// 无人车数据源配置 +struct UnmannedVehicleConfig { + std::string host; // 服务器地址 + int port; // 服务器端口 + std::string status_path; // 无人车状态接口 + std::string command_path; // 无人车指令接口 + int refresh_interval_ms; // 状态数据刷新间隔 + int timeout_ms; // 连接超时时间 + int read_timeout_ms; // 读取超时时间 + AuthConfig auth; // 认证配置 +}; + +// UnmannedVehicleConfig 的 JSON 序列化/反序列化函数 +inline void to_json(json& j, const UnmannedVehicleConfig& u) { + j = json{ + {"host", u.host}, + {"port", u.port}, + {"status_path", u.status_path}, + {"command_path", u.command_path}, + {"refresh_interval_ms", u.refresh_interval_ms}, + {"timeout_ms", u.timeout_ms}, + {"read_timeout_ms", u.read_timeout_ms}, + {"auth", u.auth} + }; +} + +inline void from_json(const json& j, UnmannedVehicleConfig& u) { + j.at("host").get_to(u.host); + j.at("port").get_to(u.port); + j.at("status_path").get_to(u.status_path); + j.at("command_path").get_to(u.command_path); + j.at("refresh_interval_ms").get_to(u.refresh_interval_ms); + j.at("timeout_ms").get_to(u.timeout_ms); + j.at("read_timeout_ms").get_to(u.read_timeout_ms); + j.at("auth").get_to(u.auth); +} + +// 红绿灯数据源配置 +struct TrafficLightConfig { + std::string host; // 服务器地址 + int port; // 服务器端口 + std::string signal_path; // 红绿灯信号接口 + int refresh_interval_ms; // 信号数据刷新间隔 + int timeout_ms; // 连接超时时间 + int read_timeout_ms; // 读取超时时间 + AuthConfig auth; // 认证配置 +}; + +// TrafficLightConfig 的 JSON 序列化/反序列化函数 +inline void to_json(json& j, const TrafficLightConfig& t) { + j = json{ + {"host", t.host}, + {"port", t.port}, + {"signal_path", t.signal_path}, + {"refresh_interval_ms", t.refresh_interval_ms}, + {"timeout_ms", t.timeout_ms}, + {"read_timeout_ms", t.read_timeout_ms}, + {"auth", t.auth} + }; +} + +inline void from_json(const json& j, TrafficLightConfig& t) { + j.at("host").get_to(t.host); + j.at("port").get_to(t.port); + j.at("signal_path").get_to(t.signal_path); + j.at("refresh_interval_ms").get_to(t.refresh_interval_ms); + j.at("timeout_ms").get_to(t.timeout_ms); + j.at("read_timeout_ms").get_to(t.read_timeout_ms); + j.at("auth").get_to(t.auth); +} + +// 数据源配置 +struct DataSourceConfig { + PositionDataConfig position; // 位置数据源配置 + UnmannedVehicleConfig vehicle; // 无人车数据源配置 + TrafficLightConfig traffic_light; // 红绿灯数据源配置 + + // 从系统配置创建数据源配置的静态工厂方法 + static DataSourceConfig fromSystemConfig(const SystemConfig& system_config); +}; + +// DataSourceConfig 的 JSON 序列化/反序列化函数 +inline void to_json(json& j, const DataSourceConfig& d) { + j = json{ + {"position", d.position}, + {"unmanned_vehicle", d.vehicle}, + {"traffic_light", d.traffic_light} + }; +} + +inline void from_json(const json& j, DataSourceConfig& d) { + j.at("position").get_to(d.position); + j.at("unmanned_vehicle").get_to(d.vehicle); + j.at("traffic_light").get_to(d.traffic_light); +} + #endif diff --git a/src/config/SystemConfig.h b/src/config/SystemConfig.h index 2daa5a6..7767f89 100644 --- a/src/config/SystemConfig.h +++ b/src/config/SystemConfig.h @@ -3,6 +3,7 @@ #include #include #include +#include "collector/DataSourceConfig.h" using json = nlohmann::json; @@ -45,19 +46,7 @@ public: std::vector coordinate_points; } airport; - struct DataSource { - std::string host; - uint16_t port; - std::string aircraft_path; - std::string vehicle_path; - std::string traffic_light_path; - std::string auth_path; // 认证接口路径 - std::string username; // 用户名 - std::string password; // 密码 - int refresh_interval_ms; - int timeout_ms; - int read_timeout_ms; - } data_source; + DataSourceConfig data_source; // 使用 DataSourceConfig 替换原有的 DataSource 结构 struct WebSocket { struct PositionUpdate { @@ -206,36 +195,6 @@ inline void from_json(const json& j, SystemConfig::CollisionDetection& p) { j.at("prediction").get_to(p.prediction); } -inline void to_json(json& j, const SystemConfig::DataSource& p) { - j = json{ - {"host", p.host}, - {"port", p.port}, - {"aircraft_path", p.aircraft_path}, - {"vehicle_path", p.vehicle_path}, - {"traffic_light_path", p.traffic_light_path}, - {"auth_path", p.auth_path}, - {"username", p.username}, - {"password", p.password}, - {"refresh_interval_ms", p.refresh_interval_ms}, - {"timeout_ms", p.timeout_ms}, - {"read_timeout_ms", p.read_timeout_ms} - }; -} - -inline void from_json(const json& j, SystemConfig::DataSource& p) { - j.at("host").get_to(p.host); - j.at("port").get_to(p.port); - j.at("aircraft_path").get_to(p.aircraft_path); - j.at("vehicle_path").get_to(p.vehicle_path); - j.at("traffic_light_path").get_to(p.traffic_light_path); - j.at("auth_path").get_to(p.auth_path); - j.at("username").get_to(p.username); - j.at("password").get_to(p.password); - j.at("refresh_interval_ms").get_to(p.refresh_interval_ms); - j.at("timeout_ms").get_to(p.timeout_ms); - j.at("read_timeout_ms").get_to(p.read_timeout_ms); -} - inline void to_json(json& j, const SystemConfig::Logging& p) { j = json{ {"level", p.level}, @@ -300,4 +259,5 @@ inline void from_json(const json& j, SystemConfig& config) { j.at("logging").get_to(config.logging); j.at("debug").get_to(config.debug); j.at("warning").get_to(config.warning); -} \ No newline at end of file +} + diff --git a/src/core/System.cpp b/src/core/System.cpp index 94f0808..6f790ae 100644 --- a/src/core/System.cpp +++ b/src/core/System.cpp @@ -9,7 +9,8 @@ System* System::instance_ = nullptr; -System::System() { +System::System() + : controllableVehicles_(ControllableVehicles::getInstance()) { instance_ = this; std::signal(SIGINT, signalHandler); std::signal(SIGTERM, signalHandler); @@ -48,35 +49,17 @@ bool System::initialize() { // 加载机场区域配置 airportBounds_ = std::make_unique("config/airport_bounds.json"); - - // 加载可控车辆配置 - controllableVehicles_ = std::make_unique("config/vehicle_control.json"); - Logger::info("Loaded controllable vehicles configuration"); // 初始化冲突检测器 - collisionDetector_ = std::make_unique(*airportBounds_, *controllableVehicles_); + collisionDetector_ = std::make_unique(*airportBounds_, controllableVehicles_); // 初始化红绿灯检测器 - trafficLightDetector_ = std::make_unique(intersection_config_, *controllableVehicles_, *this); + trafficLightDetector_ = std::make_unique(intersection_config_, controllableVehicles_, *this); // 创建数据采集器 dataCollector_ = std::make_unique(); // 数据采集器初始化并启动 - DataSourceConfig dataSourceConfig{ - system_config.data_source.host, - system_config.data_source.port, - system_config.data_source.aircraft_path, - system_config.data_source.vehicle_path, - system_config.data_source.traffic_light_path, - system_config.data_source.auth_path, - system_config.data_source.username, - system_config.data_source.password, - system_config.data_source.refresh_interval_ms, - system_config.data_source.timeout_ms, - system_config.data_source.read_timeout_ms - }; - WarnConfig warnConfig{ system_config.warning.warning_interval_ms, system_config.warning.log_interval_ms @@ -85,7 +68,8 @@ bool System::initialize() { // 初始化安全区 initializeSafetyZones(); - return dataCollector_->initialize(dataSourceConfig, warnConfig); + // 初始化数据采集器 + return dataCollector_->initialize(system_config.data_source, warnConfig); } catch (const std::exception& e) { Logger::error("Failed to initialize system: ", e.what()); @@ -176,12 +160,18 @@ void System::processLoop() { auto last_vehicle_update = std::chrono::steady_clock::now(); auto last_collision_update = std::chrono::steady_clock::now(); auto last_traffic_light_update = std::chrono::steady_clock::now(); - auto last_safety_zone_update = std::chrono::steady_clock::now(); // 添加安全区更新时间 + auto last_safety_zone_update = std::chrono::steady_clock::now(); + + // 添加三种数据的最后采集时间 + auto last_position_collection = std::chrono::steady_clock::now(); + auto last_vehicle_collection = std::chrono::steady_clock::now(); + auto last_traffic_light_collection = std::chrono::steady_clock::now(); + int64_t last_aircraft_timestamp = 0; int64_t last_vehicle_timestamp = 0; int64_t last_collision_timestamp = 0; int64_t last_traffic_light_timestamp = 0; - int64_t last_safety_zone_timestamp = 0; // 添加全区时间戳 + int64_t last_safety_zone_timestamp = 0; Logger::debug("数据处理循环启动"); @@ -189,12 +179,35 @@ void System::processLoop() { try { auto now = std::chrono::steady_clock::now(); const auto& system_config = SystemConfig::instance(); - auto last_data_collection = now; Logger::debug("开始获取数据..."); + // 计算各数据源是否需要采集 + bool need_position_collection = std::chrono::duration_cast( + now - last_position_collection).count() >= system_config.data_source.position.refresh_interval_ms; + + bool need_vehicle_collection = std::chrono::duration_cast( + now - last_vehicle_collection).count() >= system_config.data_source.vehicle.refresh_interval_ms; + + bool need_traffic_light_collection = std::chrono::duration_cast( + now - last_traffic_light_collection).count() >= system_config.data_source.traffic_light.refresh_interval_ms; + + // 根据需要刷新相应的数据 + if (need_position_collection || need_vehicle_collection || need_traffic_light_collection) { + dataCollector_->refresh(); // 刷新数据 + + if (need_position_collection) { + last_position_collection = now; + } + if (need_vehicle_collection) { + last_vehicle_collection = now; + } + if (need_traffic_light_collection) { + last_traffic_light_collection = now; + } + } + // 获取最新数据 - dataCollector_->refresh(); // 先刷新数据 auto aircraft = dataCollector_->getAircraftData(); auto vehicles = dataCollector_->getVehicleData(); auto traffic_lights = dataCollector_->getTrafficLightSignals(); @@ -206,9 +219,7 @@ void System::processLoop() { } for (auto& veh : vehicles) { objects.push_back(&veh); - //Logger::debug("车辆 ", veh.vehicleNo, " 类型: ", veh.type); - //Logger::debug("车辆 ", veh.vehicleNo, " 是否可控: ", veh.isControllable); - const auto* config = controllableVehicles_->findVehicle(veh.vehicleNo); + const auto* config = controllableVehicles_.findVehicle(veh.vehicleNo); if (config) { veh.type = config->type == "UNMANNED" ? MovingObjectType::UNMANNED : MovingObjectType::SPECIAL; veh.isControllable = config->type == "UNMANNED"; @@ -218,8 +229,11 @@ void System::processLoop() { // 检查安全区更新 auto safety_zone_elapsed = std::chrono::duration_cast( now - last_safety_zone_update).count(); + Logger::debug("安全区检测时间间隔: elapsed=", safety_zone_elapsed, "ms, interval=", system_config.collision_detection.update_interval_ms, "ms"); + if (safety_zone_elapsed >= system_config.collision_detection.update_interval_ms) { // 只有在数据更新时才进行检测 + Logger::debug("数据时间戳: aircraft=", last_aircraft_timestamp, ", vehicle=", last_vehicle_timestamp, ", last_safety=", last_safety_zone_timestamp); if (last_aircraft_timestamp > last_safety_zone_timestamp || last_vehicle_timestamp > last_safety_zone_timestamp) { // 更新安全区状态 @@ -232,7 +246,7 @@ void System::processLoop() { } // 检查无人车与安全区的冲突 - checkUnmannedVehicleSafetyZones(vehicles, objects); + //checkUnmannedVehicleSafetyZones(vehicles, objects); // 检查航空器更新 auto aircraft_elapsed = std::chrono::duration_cast( @@ -355,9 +369,23 @@ void System::processLoop() { last_traffic_light_update = now; } - // 计算下一次数据采集前的等待时间 - auto next_collection = last_data_collection + std::chrono::milliseconds(system_config.data_source.refresh_interval_ms); - auto wait_time = std::chrono::duration_cast(next_collection - now).count(); + // 计算下一次数据采集的等待时间 + auto next_position_collection = last_position_collection + + std::chrono::milliseconds(system_config.data_source.position.refresh_interval_ms); + + auto next_vehicle_collection = last_vehicle_collection + + std::chrono::milliseconds(system_config.data_source.vehicle.refresh_interval_ms); + + auto next_traffic_light_collection = last_traffic_light_collection + + std::chrono::milliseconds(system_config.data_source.traffic_light.refresh_interval_ms); + + // 取最小等待时间 + auto next_collection = std::min({next_position_collection, + next_vehicle_collection, + next_traffic_light_collection}); + + auto wait_time = std::chrono::duration_cast( + next_collection - now).count(); if (wait_time > 0) { Logger::debug("等待 ", wait_time, "ms 进行下一次采集"); @@ -380,8 +408,8 @@ void System::processCollisions(const std::vector& risks) { // 处理当前的碰撞风险 for (const auto& risk : risks) { // 处理 id1 和 id2 中的可控车辆 - bool id1_controllable = controllableVehicles_->isControllable(risk.id1); - bool id2_controllable = controllableVehicles_->isControllable(risk.id2); + bool id1_controllable = controllableVehicles_.isControllable(risk.id1); + bool id2_controllable = controllableVehicles_.isControllable(risk.id2); // 如果两个都不是可控车辆,跳过 if (!id1_controllable && !id2_controllable) { @@ -414,7 +442,7 @@ void System::processCollisions(const std::vector& risks) { } broadcastVehicleCommand(cmd); - controllableVehicles_->sendCommand(vehicleId, cmd); + controllableVehicles_.sendCommand(vehicleId, cmd); Logger::warning("发送告警指令到车辆: ", vehicleId, " 当前距离: ", risk.distance, "m", " 预测最小距离: ", risk.minDistance, "m", @@ -445,7 +473,7 @@ void System::processCollisions(const std::vector& risks) { } broadcastVehicleCommand(cmd); - controllableVehicles_->sendCommand(vehicleId, cmd); + controllableVehicles_.sendCommand(vehicleId, cmd); Logger::info("发送预警指令到车辆: ", vehicleId, " 当前距离: ", risk.distance, "m", " 预测最小距离: ", risk.minDistance, "m", @@ -492,7 +520,7 @@ void System::processCollisions(const std::vector& risks) { std::chrono::system_clock::now().time_since_epoch()).count(); broadcastVehicleCommand(cmd); - controllableVehicles_->sendCommand(vehicleId, cmd); + controllableVehicles_.sendCommand(vehicleId, cmd); Logger::info("发送恢复指令到车辆: ", vehicleId); } else { Logger::debug("车辆 ", vehicleId, " 仍然有风险,不发送恢复指令"); @@ -730,28 +758,21 @@ void System::updateSafetyZoneStates(const std::vector& objects) { } void System::checkSafetyZoneIntrusion(const MovingObject& obj) { - // 创建坐标转换器 - CoordinateConverter converter; - converter.setReferencePoint( - SystemConfig::instance().airport.reference_point.latitude, - SystemConfig::instance().airport.reference_point.longitude - ); - - // 转换目标位置到本地坐标系 - Vector2D position = converter.toLocalXY(obj.geo.latitude, obj.geo.longitude); Logger::debug("检查安全区入侵: id=", obj.id, ", type=", obj.isAircraft() ? "飞机" : (obj.isSpecialVehicle() ? "特勤车" : "其他"), - ", position=(", position.x, ",", position.y, ")"); + ", position=(", obj.position.x, ",", obj.position.y, ")"); // 检查每个安全区 for (auto& [id, zone] : safetyZones_) { - // 检查是否在安全区内,同时会尝试设置安全区类型 + // 先检查是否在安全区内 if (zone->isObjectInZone(obj)) { - zone->setState(SafetyZoneState::ACTIVE); - Logger::debug("目标 ", obj.id, " 进入路口 ", id, " 安全区, 类型: ", - zone->getType() == SafetyZoneType::AIRCRAFT ? "飞机" : "特勤车", - ", 半径: ", zone->getCurrentRadius(), - ", 中心点: (", zone->getCenter().x, ",", zone->getCenter().y, ")"); + // 如果在区内,尝试激活安全区 + if (zone->tryActivate(obj)) { + Logger::debug("目标 ", obj.id, " 进入路口 ", id, " 安全区, 类型: ", + zone->getType() == SafetyZoneType::AIRCRAFT ? "飞机" : "特勤车", + ", 半径: ", zone->getCurrentRadius(), + ", 中心点=(", zone->getCenter().x, ",", zone->getCenter().y, ")"); + } } } } @@ -765,8 +786,10 @@ void System::checkUnmannedVehicleSafetyZones(const std::vector& vehicle // 遍历所有路口安全区 for (const auto& [intersectionId, zone] : safetyZones_) { + Logger::debug("检查路口 ", intersectionId, " 安全区..."); // 如果安全区未激活,跳过 if (zone->getState() == SafetyZoneState::INACTIVE) { + Logger::debug("路口 ", intersectionId, " 安全区未激活,跳过"); continue; } @@ -805,7 +828,7 @@ void System::checkUnmannedVehicleSafetyZones(const std::vector& vehicle std::chrono::system_clock::now().time_since_epoch()).count(); broadcastVehicleCommand(cmd); - controllableVehicles_->sendCommand(vehicle.id, cmd); + controllableVehicles_.sendCommand(vehicle.id, cmd); lastVehiclesWithSafetyZoneRisk_.erase(it); } else if (hasRisk) { @@ -823,7 +846,7 @@ bool System::handleSafetyZoneRisk(const Vehicle& vehicle, CommandType cmdType, const std::string& riskLevel) { // 检查是否为无人车 - if (!controllableVehicles_->isControllable(vehicle.id)) { + if (!controllableVehicles_.isControllable(vehicle.id)) { return false; } @@ -871,7 +894,7 @@ bool System::handleSafetyZoneRisk(const Vehicle& vehicle, } broadcastVehicleCommand(cmd); - controllableVehicles_->sendCommand(vehicle.id, cmd); + controllableVehicles_.sendCommand(vehicle.id, cmd); CollisionRisk risk; risk.id1 = vehicle.id; diff --git a/src/core/System.h b/src/core/System.h index c9ad53b..2f2da10 100644 --- a/src/core/System.h +++ b/src/core/System.h @@ -75,7 +75,7 @@ private: std::thread processThread_; std::unique_ptr airportBounds_; - std::unique_ptr controllableVehicles_; + ControllableVehicles& controllableVehicles_{ControllableVehicles::getInstance()}; std::unique_ptr collisionDetector_; std::unique_ptr trafficLightDetector_; std::unique_ptr dataCollector_; diff --git a/src/detector/CollisionDetector.cpp b/src/detector/CollisionDetector.cpp index 0f4a9f2..18b7219 100644 --- a/src/detector/CollisionDetector.cpp +++ b/src/detector/CollisionDetector.cpp @@ -8,7 +8,7 @@ CollisionDetector::CollisionDetector(const AirportBounds& bounds, const ControllableVehicles& controllableVehicles) : airportBounds_(bounds) , vehicleTree_(bounds.getAirportBounds(), 8) // 使用机场总边界初始化四叉树 - , controllableVehicles_(&controllableVehicles) { + , controllableVehicles_(controllableVehicles) { // 记录初始化信息 const auto& airportBounds = bounds.getAirportBounds(); @@ -37,7 +37,7 @@ void CollisionDetector::updateTraffic(const std::vector& aircraft, // 根据配置设置车辆类型 Vehicle updatedVehicle = vehicle; - const auto* config = controllableVehicles_->findVehicle(vehicle.vehicleNo); + const auto* config = controllableVehicles_.findVehicle(vehicle.vehicleNo); if (config) { if (config->type == "UNMANNED") { updatedVehicle.type = MovingObjectType::UNMANNED; diff --git a/src/detector/CollisionDetector.h b/src/detector/CollisionDetector.h index 27c3e7b..c0d75a5 100644 --- a/src/detector/CollisionDetector.h +++ b/src/detector/CollisionDetector.h @@ -74,7 +74,7 @@ private: const AirportBounds& airportBounds_; QuadTree vehicleTree_; std::vector aircraftData_; - const ControllableVehicles* controllableVehicles_; + const ControllableVehicles& controllableVehicles_; // 冲突记录映射表:<(id1,id2), CollisionRecord> std::unordered_map, CollisionRecord, CollisionPairHash> collisionRecords_; diff --git a/src/detector/SafetyZone.cpp b/src/detector/SafetyZone.cpp index 62c8c04..0cb4372 100644 --- a/src/detector/SafetyZone.cpp +++ b/src/detector/SafetyZone.cpp @@ -37,96 +37,32 @@ void SafetyZone::resetType() { Logger::debug("重置安全区类型为 NONE"); } -bool SafetyZone::trySetType(const MovingObject& object) { - // 判断目标类型 - bool isAircraft = object.isAircraft(); - bool isSpecialVehicle = object.isSpecialVehicle(); - - // 如果既不是飞机也不是特勤车,返回 false - if (!isAircraft && !isSpecialVehicle) { - return false; +double SafetyZone::getObjectRadius(const MovingObject& object) const { + const auto& config = SystemConfig::instance().collision_detection.prediction; + if (object.isAircraft()) { + double radius = config.aircraft_size / 2.0; + Logger::debug("目标 ", object.id, " 是飞机,尺寸半径: ", radius); + return radius; + } else if (object.isSpecialVehicle()) { + double radius = config.vehicle_size / 2.0; + Logger::debug("目标 ", object.id, " 是特勤车,尺寸半径: ", radius); + return radius; } - - // 如果安全区已有类型,检查是否可以改变 - if (type_ != SafetyZoneType::NONE) { - // 如果当前类型与目标类型不匹配,不允许改变 - if ((type_ == SafetyZoneType::AIRCRAFT && !isAircraft) || - (type_ == SafetyZoneType::VEHICLE && !isSpecialVehicle)) { - return false; - } - // 如果类型匹配,保持当前类型 + return 0.0; +} + +bool SafetyZone::isTypeMatched(const MovingObject& object) const { + // 如果安全区类型未设置,返回 true + if (type_ == SafetyZoneType::NONE) { return true; } - // 设置新的类型和尺寸 - if (isAircraft) { - type_ = SafetyZoneType::AIRCRAFT; - currentRadius_ = aircraftRadius_; - state_ = SafetyZoneState::ACTIVE; // 激活安全区 - Logger::debug("安全区设置为飞机类型,半径: ", currentRadius_); - } else { - type_ = SafetyZoneType::VEHICLE; - currentRadius_ = specialVehicleRadius_; - state_ = SafetyZoneState::ACTIVE; // 激活安全区 - Logger::debug("安全区设置为特勤车类型,半径: ", currentRadius_); - } - - return true; -} - -bool SafetyZone::isObjectInZone(const MovingObject& object) const { - // 如果是无人车,直接返回 false + // 如果是无人车,返回 true if (object.isUnmannedVehicle()) { - Logger::debug("目标 ", object.id, " 是无人车,不触发安全区"); - return false; + return true; } - // 从 SystemConfig 获取物体尺寸(半长度) - const auto& config = SystemConfig::instance().collision_detection.prediction; - double objectRadius = 0.0; - - // 获取物体半径 - if (object.isAircraft()) { - objectRadius = config.aircraft_size / 2.0; - Logger::debug("目标 ", object.id, " 是飞机,尺寸半径: ", objectRadius); - } else if (object.isSpecialVehicle()) { - objectRadius = config.vehicle_size / 2.0; - Logger::debug("目标 ", object.id, " 是特勤车,尺寸半径: ", objectRadius); - } else { - return false; - } - - // 如果安全区类型未设置,尝试设置类型 - if (type_ == SafetyZoneType::NONE) { - // 临时设置类型和半径来检查是否在区内 - SafetyZoneType tempType = object.isAircraft() ? SafetyZoneType::AIRCRAFT : SafetyZoneType::VEHICLE; - double tempRadius = object.isAircraft() ? aircraftRadius_ : specialVehicleRadius_; - - // 暂存当前值 - auto currentType = type_; - auto currentRadius = currentRadius_; - - // 临时设置类型和半径 - const_cast(this)->type_ = tempType; - const_cast(this)->currentRadius_ = tempRadius; - - // 检查是否在区内 - bool inZone = isInZone(object.position); - - // 如果在区内,保持新的类型和半径,否则恢复原值 - if (!inZone) { - const_cast(this)->type_ = currentType; - const_cast(this)->currentRadius_ = currentRadius; - } else { - // 设置状态为激活 - const_cast(this)->state_ = SafetyZoneState::ACTIVE; - Logger::debug("安全区设置为", object.isAircraft() ? "飞机" : "特勤车", "类型,半径: ", tempRadius); - } - - return inZone; - } - - // 如果类型已设置,检查是否匹配 + // 如果安全区类型已设置,检查是否匹配 if ((type_ == SafetyZoneType::AIRCRAFT && !object.isAircraft()) || (type_ == SafetyZoneType::VEHICLE && !object.isSpecialVehicle())) { Logger::debug("目标 ", object.id, " 类型与安全区类型不匹配,当前安全区类型: ", @@ -134,6 +70,57 @@ bool SafetyZone::isObjectInZone(const MovingObject& object) const { return false; } - // 使用 isInZone 检查是否在区内 - return isInZone(object.position); + return true; +} + +bool SafetyZone::isObjectInZone(const MovingObject& object) const { + // 计算点到中心的距离 + double dx = object.position.x - center_.x; + double dy = object.position.y - center_.y; + double distance = std::sqrt(dx * dx + dy * dy); + + // 如果安全区类型未设置,使用对应的临时半径进行检查 + double checkRadius = (type_ == SafetyZoneType::NONE) + ? (object.isAircraft() ? aircraftRadius_ : specialVehicleRadius_) + : currentRadius_; + + Logger::debug("检查目标 ", object.id, " 是否在安全区内: ", + "dx=", dx, ", dy=", dy, ", distance=", distance, + ", checkRadius=", checkRadius, + ", type=", type_ == SafetyZoneType::NONE ? "NONE" : + (type_ == SafetyZoneType::AIRCRAFT ? "AIRCRAFT" : "VEHICLE"), + ", center=(", center_.x, ",", center_.y, ")", + ", object=(", object.position.x, ",", object.position.y, ")"); + + return distance <= checkRadius; +} + +bool SafetyZone::tryActivate(const MovingObject& object) { + // 如果是无人车,不激活安全区 + if (object.isUnmannedVehicle()) { + Logger::debug("目标 ", object.id, " 是无人车,不激活安全区"); + return false; + } + + // 如果类型已设置且不匹配,不激活 + if (!isTypeMatched(object)) { + return false; + } + + // 检查是否在区内 + bool inZone = isObjectInZone(object); + if (!inZone) { + return false; + } + + // 如果安全区类型未设置,设置新的类型和半径 + if (type_ == SafetyZoneType::NONE) { + type_ = object.isAircraft() ? SafetyZoneType::AIRCRAFT : SafetyZoneType::VEHICLE; + currentRadius_ = object.isAircraft() ? aircraftRadius_ : specialVehicleRadius_; + Logger::debug("安全区设置为", object.isAircraft() ? "飞机" : "特勤车", "类型,半径: ", currentRadius_); + } + + // 激活安全区 + state_ = SafetyZoneState::ACTIVE; + return true; } \ No newline at end of file diff --git a/src/detector/SafetyZone.h b/src/detector/SafetyZone.h index 6a101a5..5a96803 100644 --- a/src/detector/SafetyZone.h +++ b/src/detector/SafetyZone.h @@ -34,9 +34,12 @@ public: // 检查点是否在安全区内 bool isInZone(const Vector2D& point) const; - // 检查目标是否在安全区内 + // 检查目标是否在安全区内 - 纯检测函数,不修改状态 bool isObjectInZone(const MovingObject& object) const; + // 尝试更新安全区状态 - 处理状态更新 + bool tryActivate(const MovingObject& object); + // 获取中心点 const Vector2D& getCenter() const { return center_; } @@ -52,9 +55,12 @@ private: double aircraftRadius_; // 飞机安全区半径 double specialVehicleRadius_; // 特勤车安全区半径 double currentRadius_; // 当前安全区半径 - SafetyZoneState state_; // 当前状态 - SafetyZoneType type_; // 当前类型 + SafetyZoneState state_; // 当前状态 + SafetyZoneType type_; // 当前类型 - // 尝试设置安全区类型和尺寸 - bool trySetType(const MovingObject& object); + // 检查物体类型是否匹配当前安全区类型 + bool isTypeMatched(const MovingObject& object) const; + + // 获取物体的有效半径 + double getObjectRadius(const MovingObject& object) const; }; \ No newline at end of file diff --git a/src/detector/TrafficLightDetector.cpp b/src/detector/TrafficLightDetector.cpp index d513e14..62ddf4b 100644 --- a/src/detector/TrafficLightDetector.cpp +++ b/src/detector/TrafficLightDetector.cpp @@ -5,7 +5,7 @@ #include TrafficLightDetector::TrafficLightDetector(const IntersectionConfig& intersectionConfig, - const ControllableVehicles& controllableVehicles, + ControllableVehicles& controllableVehicles, System& system) : intersection_config_(intersectionConfig) , controllable_vehicles_(controllableVehicles) @@ -68,4 +68,4 @@ void TrafficLightDetector::sendSignalCommand(const std::string& vehicleNo, Signa Logger::debug("发送信号灯指令到车辆: ", vehicleNo, " 路口: ", cmd.intersectionId, " 状态: ", state == SignalState::RED ? "红灯" : state == SignalState::GREEN ? "绿灯" : "黄灯"); -} \ No newline at end of file +} \ No newline at end of file diff --git a/src/detector/TrafficLightDetector.h b/src/detector/TrafficLightDetector.h index f425f71..d90124a 100644 --- a/src/detector/TrafficLightDetector.h +++ b/src/detector/TrafficLightDetector.h @@ -10,7 +10,7 @@ class System; class TrafficLightDetector { public: TrafficLightDetector(const IntersectionConfig& intersectionConfig, - const ControllableVehicles& controllableVehicles, + ControllableVehicles& controllableVehicles, System& system); void processSignal(const TrafficLightSignal& signal, @@ -18,7 +18,7 @@ public: private: const IntersectionConfig& intersection_config_; - const ControllableVehicles& controllable_vehicles_; + ControllableVehicles& controllable_vehicles_; System& system_; TrafficLightSignal current_signal_; diff --git a/src/network/HTTPDataSource.cpp b/src/network/HTTPDataSource.cpp index 1fee1d3..4da56c1 100644 --- a/src/network/HTTPDataSource.cpp +++ b/src/network/HTTPDataSource.cpp @@ -6,16 +6,19 @@ using json = nlohmann::json; size_t HTTPDataSource::WriteCallback(void* contents, size_t size, size_t nmemb, void* userp) { - ((std::string*)userp)->append((char*)contents, size * nmemb); - return size * nmemb; + size_t total_size = size * nmemb; + std::string* response = static_cast(userp); + response->append(static_cast(contents), total_size); + return total_size; +} + +size_t HTTPDataSource::DebugCallback(CURL* handle, curl_infotype type, char* data, size_t size, void* userp) { + return 0; } HTTPDataSource::HTTPDataSource(const DataSourceConfig& config) : config_(config) - , host_(config.host) - , port_(std::to_string(config.port)) - , last_health_check_(std::chrono::steady_clock::now()) - , is_authenticated_(false) { + , last_health_check_(std::chrono::steady_clock::now()) { curl_ = curl_easy_init(); if (!curl_) { Logger::error("Failed to initialize CURL"); @@ -37,9 +40,7 @@ bool HTTPDataSource::connect() { return false; } } - - // 进行认证 - return authenticate(); + return true; } void HTTPDataSource::disconnect() { @@ -55,7 +56,7 @@ bool HTTPDataSource::isAvailable() const { bool HTTPDataSource::tryReconnect() { if (is_reconnecting_) { - return false; // 已经在重连中 + return false; } is_reconnecting_ = true; @@ -65,24 +66,21 @@ bool HTTPDataSource::tryReconnect() { auto elapsed = std::chrono::duration_cast( now - last_connect_attempt_).count(); - if (elapsed < config_.refresh_interval_ms) { + if (elapsed < config_.position.timeout_ms) { is_reconnecting_ = false; - return false; // 距离上次尝试时间太短 + return false; } - Logger::info("Attempting to reconnect to ", config_.host, ":", config_.port); last_connect_attempt_ = now; for (int retry = 0; retry < MAX_RETRIES; ++retry) { if (connect()) { - Logger::info("Successfully reconnected"); is_reconnecting_ = false; return true; } if (retry < MAX_RETRIES - 1) { - Logger::info("Reconnection attempt ", retry + 1, " failed, retrying..."); - std::this_thread::sleep_for(std::chrono::milliseconds(config_.refresh_interval_ms/3)); + std::this_thread::sleep_for(std::chrono::milliseconds(config_.position.timeout_ms/3)); } } @@ -103,7 +101,7 @@ bool HTTPDataSource::checkConnectionHealth() { now - last_health_check_).count(); if (elapsed < HEALTH_CHECK_INTERVAL) { - return true; // 距离上次检查时间不够长 + return true; } last_health_check_ = now; @@ -118,108 +116,125 @@ bool HTTPDataSource::ensureConnected() { return tryReconnect(); } -bool HTTPDataSource::sendRequest(const std::string& path, std::string& response, HttpMethod method) { +bool HTTPDataSource::sendRequest(const std::string& url, const AuthState* auth_state, + std::string& response, HttpMethod method, const std::string& body) { if (!curl_) { Logger::error("CURL not initialized"); return false; } - // 检查认证状态 - if (!is_authenticated_) { - Logger::error("Not authenticated"); - if (!authenticate()) { - return false; - } - } - - std::string url = "http://" + host_ + ":" + port_ + path; - Logger::debug("Sending request to: ", url); - curl_easy_reset(curl_); curl_easy_setopt(curl_, CURLOPT_URL, url.c_str()); curl_easy_setopt(curl_, CURLOPT_WRITEFUNCTION, WriteCallback); curl_easy_setopt(curl_, CURLOPT_WRITEDATA, &response); - curl_easy_setopt(curl_, CURLOPT_TIMEOUT, config_.read_timeout_ms / 1000); - curl_easy_setopt(curl_, CURLOPT_CONNECTTIMEOUT, config_.timeout_ms / 1000); + curl_easy_setopt(curl_, CURLOPT_TIMEOUT, config_.position.timeout_ms / 1000); + curl_easy_setopt(curl_, CURLOPT_CONNECTTIMEOUT, config_.position.timeout_ms / 1000); curl_easy_setopt(curl_, CURLOPT_NOSIGNAL, 1L); - // 根据方法设置不同的选项 if (method == HttpMethod::GET) { curl_easy_setopt(curl_, CURLOPT_HTTPGET, 1L); + curl_easy_setopt(curl_, CURLOPT_POST, 0L); } else if (method == HttpMethod::POST) { curl_easy_setopt(curl_, CURLOPT_POST, 1L); + curl_easy_setopt(curl_, CURLOPT_HTTPGET, 0L); + if (!body.empty()) { + curl_easy_setopt(curl_, CURLOPT_POSTFIELDS, body.c_str()); + } else { + curl_easy_setopt(curl_, CURLOPT_POSTFIELDS, ""); + } } - // 添加 HTTP 头 struct curl_slist* headers = nullptr; headers = curl_slist_append(headers, "Accept: application/json"); headers = curl_slist_append(headers, "Cache-Control: no-cache"); + headers = curl_slist_append(headers, "Expect:"); - // 添加认证 token - if (!auth_token_.empty()) { - std::string auth_header = "Authorization: " + auth_token_; + if (method == HttpMethod::POST) { + headers = curl_slist_append(headers, "Content-Type: application/json"); + } + + if (auth_state && auth_state->is_authenticated && !auth_state->token.empty()) { + std::string auth_header = "Authorization: " + auth_state->token; headers = curl_slist_append(headers, auth_header.c_str()); } curl_easy_setopt(curl_, CURLOPT_HTTPHEADER, headers); + response.clear(); CURLcode res = curl_easy_perform(curl_); curl_slist_free_all(headers); if (res != CURLE_OK) { - Logger::error("Failed to send request: ", curl_easy_strerror(res)); + Logger::error("请求失败: ", curl_easy_strerror(res)); return false; } long http_code = 0; curl_easy_getinfo(curl_, CURLINFO_RESPONSE_CODE, &http_code); - // 如果返回 401,尝试重新认证 - if (http_code == 401) { - Logger::warning("Token expired, trying to re-authenticate"); - if (authenticate()) { - // 重新发送请求 - return sendRequest(path, response, method); - } - return false; - } - if (http_code != 200) { - Logger::error("HTTP request failed with code: ", http_code); + Logger::error("HTTP 请求失败,状态码: ", http_code); return false; } return true; } -bool HTTPDataSource::fetchAircraftData(std::vector& aircraft) { +bool HTTPDataSource::fetchPositionAircraftData(std::vector& aircraft) { std::lock_guard lock(mutex_); if (!ensureConnected()) { + Logger::error("连接失败"); return false; } + if (!ensureAuthenticated(config_.position.auth, + config_.position.host, + config_.position.port, + position_auth_, + DataSourceType::POSITION)) { + Logger::error("认证失败"); + return false; + } + + std::string url = "http://" + config_.position.host + ":" + + std::to_string(config_.position.port) + + config_.position.aircraft_path; + std::string response; - if (!sendRequest(config_.aircraft_path, response, HttpMethod::GET)) { + if (!sendRequest(url, &position_auth_, response, HttpMethod::GET)) { + Logger::error("请求失败"); return false; } - return parseAircraftResponse(response, aircraft); + return parsePositionAircraftResponse(response, aircraft); } -bool HTTPDataSource::fetchVehicleData(std::vector& vehicles) { +bool HTTPDataSource::fetchPositionVehicleData(std::vector& vehicles) { std::lock_guard lock(mutex_); if (!ensureConnected()) { return false; } + if (!ensureAuthenticated(config_.position.auth, + config_.position.host, + config_.position.port, + position_auth_, + DataSourceType::POSITION)) { + return false; + } + + std::string url = "http://" + config_.position.host + ":" + + std::to_string(config_.position.port) + + config_.position.vehicle_path; + std::string response; - if (!sendRequest(config_.vehicle_path, response, HttpMethod::GET)) { + if (!sendRequest(url, &position_auth_, response, HttpMethod::GET)) { return false; } - return parseVehicleResponse(response, vehicles); + return parsePositionVehicleResponse(response, vehicles); } bool HTTPDataSource::fetchTrafficLightSignals(std::vector& signals) { @@ -229,224 +244,164 @@ bool HTTPDataSource::fetchTrafficLightSignals(std::vector& s return false; } + if (!ensureAuthenticated(config_.traffic_light.auth, + config_.traffic_light.host, + config_.traffic_light.port, + traffic_light_auth_, + DataSourceType::TRAFFIC_LIGHT)) { + return false; + } + + std::string url = "http://" + config_.traffic_light.host + ":" + + std::to_string(config_.traffic_light.port) + + config_.traffic_light.signal_path; + std::string response; - if (!sendRequest(config_.traffic_light_path, response, HttpMethod::GET)) { + if (!sendRequest(url, &traffic_light_auth_, response, HttpMethod::GET)) { return false; } return parseTrafficLightResponse(response, signals); } -bool HTTPDataSource::parseTrafficLightResponse(const std::string& response, std::vector& signals) { +bool HTTPDataSource::sendUnmannedVehicleCommand(const std::string& vehicle_id, const VehicleCommand& command) { + std::lock_guard lock(mutex_); + + if (!ensureConnected()) { + return false; + } + + if (!ensureAuthenticated(config_.vehicle.auth, + config_.vehicle.host, + config_.vehicle.port, + unmanned_vehicle_auth_, + DataSourceType::UNMANNED)) { + return false; + } + + std::string url = "http://" + config_.vehicle.host + ":" + + std::to_string(config_.vehicle.port) + + config_.vehicle.command_path; + + std::stringstream transId; + transId << std::hex << std::chrono::system_clock::now().time_since_epoch().count(); + + nlohmann::json request = { + {"transId", transId.str()}, + {"timestamp", command.timestamp}, + {"vehicleID", command.vehicleId}, + {"commandType", [&]() { + switch (command.type) { + case CommandType::SIGNAL: return "SIGNAL"; + case CommandType::ALERT: return "ALERT"; + case CommandType::WARNING: return "WARNING"; + case CommandType::RESUME: return "RESUME"; + default: return "UNKNOWN"; + } + }()}, + {"commandReason", [&]() { + switch (command.reason) { + case CommandReason::TRAFFIC_LIGHT: return "TRAFFIC_LIGHT"; + case CommandReason::AIRCRAFT_CROSSING: return "AIRCRAFT_CROSSING"; + case CommandReason::SPECIAL_VEHICLE: return "SPECIAL_VEHICLE"; + case CommandReason::AIRCRAFT_PUSH: return "AIRCRAFT_PUSH"; + case CommandReason::RESUME_TRAFFIC: return "RESUME_TRAFFIC"; + default: return "UNKNOWN"; + } + }()}, + {"latitude", command.latitude}, + {"longitude", command.longitude} + }; + + if (command.type == CommandType::SIGNAL) { + request["signalState"] = command.signalState == SignalState::RED ? "RED" : "GREEN"; + request["intersectionId"] = command.intersectionId; + } + + if (command.type == CommandType::ALERT || command.type == CommandType::WARNING) { + request["relativeSpeed"] = command.relativeSpeed; + request["relativeMotionX"] = command.relativeMotionX; + request["relativeMotionY"] = command.relativeMotionY; + request["minDistance"] = command.minDistance; + } + + std::string response; + if (!sendRequest(url, &unmanned_vehicle_auth_, response, HttpMethod::POST, request.dump())) { + return false; + } + try { - json j = json::parse(response); - - if (!j.is_array()) { - Logger::error("Invalid traffic light response format: expected array"); + nlohmann::json j = nlohmann::json::parse(response); + if (!j.contains("code") || !j.contains("msg")) { + Logger::error("Invalid command response format"); return false; } - signals.clear(); - signals.reserve(j.size()); - - for (const auto& item : j) { - TrafficLightSignal signal; - - // 解析必需字段 - if (!item.contains("id") || !item.contains("state")) { - Logger::error("Missing required fields in traffic light signal"); - continue; - } - - signal.trafficLightId = item["id"].get(); - - // 支持数字或字符串类型的状态 - if (item["state"].is_number()) { - signal.status = static_cast(item["state"].get()); - } else { - signal.status = TrafficLightSignal::parseStatus(item["state"].get()); - } - - // 解析可选字段 - if (item.contains("timestamp")) { - signal.timestamp = item["timestamp"].get(); - } - - signals.push_back(signal); + if (j["code"].get() != 200) { + Logger::error("Command failed: ", j["msg"].get()); + return false; } - return !signals.empty(); - } - catch (const json::exception& e) { - Logger::error("Failed to parse traffic light response: ", e.what()); - return false; + return true; } catch (const std::exception& e) { - Logger::error("Error processing traffic light response: ", e.what()); + Logger::error("Failed to parse command response: ", e.what()); return false; } } -bool HTTPDataSource::parseVehicleResponse(const std::string& response, std::vector& vehicles) { +bool HTTPDataSource::fetchUnmannedVehicleStatus(const std::string& vehicle_id, std::string& status) { + std::lock_guard lock(mutex_); + + if (!ensureConnected()) { + return false; + } + + if (!ensureAuthenticated(config_.vehicle.auth, + config_.vehicle.host, + config_.vehicle.port, + unmanned_vehicle_auth_, + DataSourceType::UNMANNED)) { + return false; + } + + std::string url = "http://" + config_.vehicle.host + ":" + + std::to_string(config_.vehicle.port) + + config_.vehicle.status_path + "?vehicleId=" + vehicle_id; + + std::string response; + if (!sendRequest(url, &unmanned_vehicle_auth_, response, HttpMethod::GET)) { + return false; + } + try { - json j = json::parse(response); - - // 检查顶层结构 + nlohmann::json j = nlohmann::json::parse(response); if (!j.contains("status") || !j.contains("data")) { - Logger::error("Invalid vehicle response format: missing status or data field"); - return false; - } - - // 检查状态码 - int status = j["status"].get(); - if (status != 200) { - Logger::error("Vehicle response error, status: " + std::to_string(status)); - return false; - } - - // 获取数据数组 - const auto& data = j["data"]; - if (!data.is_array()) { - Logger::error("Invalid vehicle response format: data is not an array"); + Logger::error("Invalid vehicle status response format"); return false; } - vehicles.clear(); - vehicles.reserve(data.size()); - - for (const auto& item : data) { - Vehicle veh; - - // 解析必需字段 - if (!item.contains("vehicleNo") || !item.contains("latitude") || - !item.contains("longitude") || !item.contains("time")) { - Logger::error("Missing required fields in vehicle data"); - continue; - } - - veh.vehicleNo = item["vehicleNo"].get(); - veh.id = veh.vehicleNo; // 使用车辆号作为ID - veh.geo.latitude = item["latitude"].get(); - veh.geo.longitude = item["longitude"].get(); - - // 时间戳转换 - veh.timestamp = item["time"].get(); - - // 解析可选字段 - if (item.contains("direction")) { - veh.heading = item["direction"].get(); - } - if (item.contains("speed")) { - veh.speed = item["speed"].get(); - } - - // 更新位置信息 - veh.position = coordinateConverter_.toLocalXY(veh.geo.latitude, veh.geo.longitude); - veh.updateMotion(veh.geo, veh.timestamp); // 更新速度和航向 - - vehicles.push_back(veh); + if (j["status"].get() != 200) { + Logger::error("Failed to get vehicle status"); + return false; } - return !vehicles.empty(); - } - catch (const json::exception& e) { - Logger::error("Failed to parse vehicle response: ", e.what()); - return false; + status = j["data"].dump(); + return true; } catch (const std::exception& e) { - Logger::error("Error processing vehicle response: ", e.what()); + Logger::error("Failed to parse vehicle status response: ", e.what()); return false; } } -bool HTTPDataSource::parseAircraftResponse(const std::string& response, std::vector& aircraft) { - try { - json j = json::parse(response); - - // 检查顶层结构 - if (!j.contains("status") || !j.contains("data")) { - Logger::error("Invalid aircraft response format: missing status or data field"); - return false; - } - - // 检查状态码 - int status = j["status"].get(); - if (status != 200) { - Logger::error("Aircraft response error, status: " + std::to_string(status)); - return false; - } - - // 获取数据数组 - const auto& data = j["data"]; - if (!data.is_array()) { - Logger::error("Invalid aircraft response format: data is not an array"); - return false; - } - - aircraft.clear(); - aircraft.reserve(data.size()); - - // 获取当前时间戳,用于临时替代 - uint64_t current_timestamp = std::chrono::duration_cast( - std::chrono::system_clock::now().time_since_epoch()).count(); - - for (const auto& item : data) { - Aircraft ac; - - // 解析必需字段 - if (!item.contains("flightNo") || !item.contains("latitude") || - !item.contains("longitude") || !item.contains("time")) { - Logger::error("Missing required fields in aircraft data"); - continue; - } - - ac.flightNo = item["flightNo"].get(); - ac.id = ac.flightNo; // 使用航班号作为ID - ac.geo.latitude = item["latitude"].get(); - ac.geo.longitude = item["longitude"].get(); - - // 时间戳处理:暂时使用本地时间戳 - // 注意:机场给的时间戳可能是 double 格式,我们暂时不使用它 - ac.timestamp = current_timestamp; - - // 解析可选字段 - if (item.contains("altitude")) { - ac.altitude = item["altitude"].get(); - } else { - ac.altitude = 0.0; // 默认值 - } - - if (item.contains("trackNumber")) { - // 航迹号可能是数字类型,需要转换为字符串 - if (item["trackNumber"].is_number()) { - ac.trackNumber = std::to_string(item["trackNumber"].get()); - } else { - ac.trackNumber = item["trackNumber"].get(); - } - } else { - ac.trackNumber = "TN" + ac.flightNo.substr(2); // 默认使用航班号生成跟踪号 - } - - // 更新位置信息 - ac.position = coordinateConverter_.toLocalXY(ac.geo.latitude, ac.geo.longitude); - ac.updateMotion(ac.geo, ac.timestamp); // 更新速度和航向 - - aircraft.push_back(ac); - } - - return !aircraft.empty(); +bool HTTPDataSource::authenticatePosition(const AuthConfig& auth_config, + const std::string& host, int port, AuthState& auth_state) { + if (!auth_config.auth_required) { + auth_state.is_authenticated = true; + return true; } - catch (const json::exception& e) { - Logger::error("Failed to parse aircraft response: ", e.what()); - return false; - } - catch (const std::exception& e) { - Logger::error("Error processing aircraft response: ", e.what()); - return false; - } -} - -bool HTTPDataSource::authenticate() { + std::lock_guard lock(auth_mutex_); if (!curl_) { @@ -454,70 +409,193 @@ bool HTTPDataSource::authenticate() { return false; } - // 构造带参数的认证URL - std::string url = "http://" + host_ + ":" + port_ + config_.auth_path + - "?username=" + config_.username + - "&password=" + config_.password; - Logger::debug("Authentication URL: ", url); + std::string url = "http://" + host + ":" + std::to_string(port) + + auth_config.auth_path + "?username=" + auth_config.username + + "&password=" + auth_config.password; std::string response; - - // 设置CURL选项 - curl_easy_reset(curl_); - curl_easy_setopt(curl_, CURLOPT_URL, url.c_str()); - curl_easy_setopt(curl_, CURLOPT_POST, 1L); // 使用POST方法 - curl_easy_setopt(curl_, CURLOPT_POSTFIELDS, ""); // 空的POST数据 - curl_easy_setopt(curl_, CURLOPT_WRITEFUNCTION, WriteCallback); - curl_easy_setopt(curl_, CURLOPT_WRITEDATA, &response); - - // 设置请求头 - struct curl_slist* headers = nullptr; - headers = curl_slist_append(headers, "Accept: application/json"); - curl_easy_setopt(curl_, CURLOPT_HTTPHEADER, headers); - - // 发送请求 - CURLcode res = curl_easy_perform(curl_); - curl_slist_free_all(headers); - - if (res != CURLE_OK) { - Logger::error("Failed to authenticate: ", curl_easy_strerror(res)); - return false; - } - - // 检查响应状态码 - long http_code = 0; - curl_easy_getinfo(curl_, CURLINFO_RESPONSE_CODE, &http_code); - - if (http_code != 200) { - Logger::error("Authentication failed with HTTP code: ", http_code); - Logger::error("Response body: ", response); + if (!sendRequest(url, nullptr, response, HttpMethod::POST, "")) { + Logger::error("认证请求失败"); return false; } try { - Logger::debug("Authentication response: ", response); - - // 解析响应获取 token nlohmann::json j = nlohmann::json::parse(response); if (!j.contains("status") || !j.contains("msg") || !j.contains("data")) { - Logger::error("Authentication response missing required fields"); + Logger::error("认证响应缺少必需字段"); return false; } if (j["status"].get() != 200) { - Logger::error("Authentication failed: ", j["msg"].get()); + Logger::error("认证失败: ", j["msg"].get()); return false; } - auth_token_ = j["data"].get(); - is_authenticated_ = true; - Logger::debug("Stored token: ", auth_token_); - Logger::info("Successfully authenticated: ", j["msg"].get()); + std::string token = j["data"].get(); + if (token.substr(0, 7) != "Bearer ") { + token = "Bearer " + token; + } + auth_state.token = token; + auth_state.is_authenticated = true; + auth_state.last_auth_time = std::chrono::steady_clock::now(); + return true; } catch (const std::exception& e) { - Logger::error("Failed to parse authentication response: ", e.what()); - Logger::error("Raw response: ", response); + Logger::error("解析认证响应失败: ", e.what(), ", 响应内容: ", response); return false; } -} \ No newline at end of file +} + +bool HTTPDataSource::authenticateUnmanned(const AuthConfig& auth_config, + const std::string& host, int port, AuthState& auth_state) { + auth_state.is_authenticated = true; + return true; +} + +bool HTTPDataSource::authenticateTrafficLight(const AuthConfig& auth_config, + const std::string& host, int port, AuthState& auth_state) { + auth_state.is_authenticated = true; + return true; +} + +bool HTTPDataSource::ensureAuthenticated(const AuthConfig& auth_config, const std::string& host, + int port, AuthState& auth_state, DataSourceType type) { + if (!auth_config.auth_required) { + return true; + } + + if (!auth_state.is_authenticated) { + switch(type) { + case DataSourceType::POSITION: + return authenticatePosition(auth_config, host, port, auth_state); + case DataSourceType::UNMANNED: + return authenticateUnmanned(auth_config, host, port, auth_state); + case DataSourceType::TRAFFIC_LIGHT: + return authenticateTrafficLight(auth_config, host, port, auth_state); + default: + return false; + } + } + + return true; +} + +bool HTTPDataSource::parsePositionAircraftResponse(const std::string& response, std::vector& aircraft) { + try { + nlohmann::json j = nlohmann::json::parse(response); + if (!j.contains("status") || !j.contains("data")) { + Logger::error("Invalid aircraft response format"); + return false; + } + + if (j["status"].get() != 200) { + Logger::error("Failed to get aircraft data: ", j["msg"].get()); + return false; + } + + const auto& data = j["data"]; + aircraft.clear(); + for (const auto& item : data) { + Aircraft ac; + ac.flightNo = item["flightNo"].get(); + ac.id = ac.flightNo; + ac.geo.longitude = item["longitude"].get(); + ac.geo.latitude = item["latitude"].get(); + ac.timestamp = item["time"].get(); + + if (item.contains("altitude")) { + ac.altitude = item["altitude"].get(); + } + if (item.contains("trackNumber")) { + ac.trackNumber = item["trackNumber"].get(); + } + aircraft.push_back(ac); + } + return true; + } + catch (const std::exception& e) { + Logger::error("Failed to parse aircraft response: ", e.what()); + return false; + } +} + +bool HTTPDataSource::parsePositionVehicleResponse(const std::string& response, std::vector& vehicles) { + try { + nlohmann::json j = nlohmann::json::parse(response); + if (!j.contains("status") || !j.contains("data")) { + Logger::error("Invalid vehicle response format"); + return false; + } + + if (j["status"].get() != 200) { + Logger::error("Failed to get vehicle data: ", j["msg"].get()); + return false; + } + + const auto& data = j["data"]; + vehicles.clear(); + for (const auto& item : data) { + Vehicle vehicle; + vehicle.vehicleNo = item["vehicleNo"].get(); + vehicle.id = vehicle.vehicleNo; + vehicle.geo.longitude = item["longitude"].get(); + vehicle.geo.latitude = item["latitude"].get(); + vehicle.timestamp = item["time"].get(); + + if (item.contains("direction")) { + vehicle.heading = item["direction"].get(); + } + if (item.contains("speed")) { + vehicle.speed = item["speed"].get(); + } + vehicles.push_back(vehicle); + } + return true; + } + catch (const std::exception& e) { + Logger::error("Failed to parse vehicle response: ", e.what()); + return false; + } +} + +bool HTTPDataSource::parseTrafficLightResponse(const std::string& response, std::vector& signals) { + try { + nlohmann::json j = nlohmann::json::parse(response); + if (!j.contains("status") || !j.contains("data")) { + Logger::error("Invalid traffic light response format"); + return false; + } + + if (j["status"].get() != 200) { + Logger::error("Failed to get traffic light data: ", j["msg"].get()); + return false; + } + + const auto& data = j["data"]; + signals.clear(); + for (const auto& item : data) { + TrafficLightSignal signal; + signal.trafficLightId = item["id"].get(); + signal.status = [&]() { + int state = item["state"].get(); + switch (state) { + case 0: return SignalStatus::RED; + case 1: return SignalStatus::GREEN; + case 2: return SignalStatus::YELLOW; + default: return SignalStatus::UNKNOWN; + } + }(); + signal.timestamp = item["timestamp"].get(); + signal.intersectionId = item["intersection"].get(); + signal.latitude = item["position"]["latitude"].get(); + signal.longitude = item["position"]["longitude"].get(); + signals.push_back(signal); + } + return true; + } + catch (const std::exception& e) { + Logger::error("Failed to parse traffic light response: ", e.what()); + return false; + } +} diff --git a/src/network/HTTPDataSource.h b/src/network/HTTPDataSource.h index 7591e44..e81f0e3 100644 --- a/src/network/HTTPDataSource.h +++ b/src/network/HTTPDataSource.h @@ -10,6 +10,7 @@ #include #include "core/System.h" #include +#include "types/VehicleCommand.h" class HTTPDataSource : public DataSource { public: @@ -28,13 +29,18 @@ public: void disconnect() override; bool isAvailable() const override; - bool fetchAircraftData(std::vector& aircraft) override; - bool fetchVehicleData(std::vector& vehicles) override; + // 位置数据接口 + bool fetchPositionAircraftData(std::vector& aircraft) override; + bool fetchPositionVehicleData(std::vector& vehicles) override; + + // 无人车接口 + bool sendUnmannedVehicleCommand(const std::string& vehicle_id, const VehicleCommand& command) override; + bool fetchUnmannedVehicleStatus(const std::string& vehicle_id, std::string& status) override; + + // 红绿灯接口 bool fetchTrafficLightSignals(std::vector& signals) override; private: - std::string host_; - std::string port_; CoordinateConverter coordinateConverter_; std::mutex mutex_; CURL* curl_; @@ -45,23 +51,47 @@ private: static constexpr int HEALTH_CHECK_INTERVAL = 60; // 健康检查间隔(秒) std::atomic is_reconnecting_{false}; // 重连状态标志 - std::string auth_token_; // 认证 token - bool is_authenticated_; // 认证状态 - std::mutex auth_mutex_; // 认证相关的互斥锁 + // 每个数据源的认证状态 + struct AuthState { + bool is_authenticated = false; + std::string token; + std::chrono::steady_clock::time_point last_auth_time; + }; - bool authenticate(); // 认证方法 - bool refreshToken(); // 刷新 token + AuthState position_auth_; // 位置数据源认证状态 + AuthState unmanned_vehicle_auth_; // 无人车数据源认证状态 + AuthState traffic_light_auth_; // 红绿灯数据源认证状态 + std::mutex auth_mutex_; // 认证相关的互斥锁 + + // 认证相关方法 + bool ensureAuthenticated(const AuthConfig& auth_config, const std::string& host, + int port, AuthState& auth_state, DataSourceType type); bool tryReconnect(); bool ensureConnected(); bool checkConnectionHealth(); // 检查连接健康状况 - bool sendRequest(const std::string& path, std::string& response, HttpMethod method = HttpMethod::GET); - bool parseAircraftResponse(const std::string& response, std::vector& aircraft); - bool parseVehicleResponse(const std::string& response, std::vector& vehicles); + bool sendRequest(const std::string& url, const AuthState* auth_state, + std::string& response, HttpMethod method = HttpMethod::GET, + const std::string& body = ""); + + // 位置数据响应解析 + bool parsePositionAircraftResponse(const std::string& response, std::vector& aircraft); + bool parsePositionVehicleResponse(const std::string& response, std::vector& vehicles); + + // 红绿灯响应解析 bool parseTrafficLightResponse(const std::string& response, std::vector& signals); static size_t WriteCallback(void* contents, size_t size, size_t nmemb, void* userp); + static size_t DebugCallback(CURL* handle, curl_infotype type, char* data, size_t size, void* userp); + + // 不同数据源的认证方法 + bool authenticatePosition(const AuthConfig& auth_config, const std::string& host, + int port, AuthState& auth_state); + bool authenticateUnmanned(const AuthConfig& auth_config, const std::string& host, + int port, AuthState& auth_state); + bool authenticateTrafficLight(const AuthConfig& auth_config, const std::string& host, + int port, AuthState& auth_state); }; #endif // AIRPORT_NETWORK_HTTP_DATA_SOURCE_H diff --git a/src/types/BasicTypes.cpp b/src/types/BasicTypes.cpp index e0310ca..c4822b1 100644 --- a/src/types/BasicTypes.cpp +++ b/src/types/BasicTypes.cpp @@ -1,5 +1,6 @@ #include "types/BasicTypes.h" #include "utils/Logger.h" +#include "spatial/CoordinateConverter.h" #include double Vector2D::magnitude() const { @@ -124,15 +125,16 @@ void MovingObject::updateMotion(const GeoPosition& newPos, uint64_t newTime) { // 计算并直接更新航向,不需要平滑处理 heading = calculateHeading(prev.geo, curr.geo); - } else { - // Logger::debug("[Motion] No update: distance=", distance, "m < ", MIN_DISTANCE, - // "m or timeDiff=", timeDiff, "s < ", MIN_TIME, "s"); } } // 更新当前位置 geo = newPos; timestamp = newTime; + + // 使用坐标转换器更新平面坐标 + static CoordinateConverter converter; + position = converter.toLocalXY(geo.latitude, geo.longitude); } void MovingObject::copyHistoryFrom(const MovingObject& other) { diff --git a/src/vehicle/ControllableVehicles.cpp b/src/vehicle/ControllableVehicles.cpp index 06017f0..219ff62 100644 --- a/src/vehicle/ControllableVehicles.cpp +++ b/src/vehicle/ControllableVehicles.cpp @@ -4,6 +4,16 @@ #include #include +// 定义静态成员变量 +ControllableVehicles* ControllableVehicles::instance_ = nullptr; + +ControllableVehicles& ControllableVehicles::getInstance() { + if (instance_ == nullptr) { + instance_ = new ControllableVehicles("config/vehicle_control.json"); + } + return *instance_; +} + ControllableVehicles::ControllableVehicles(const std::string& configFile) : http_client_(std::make_unique()) { if (!configFile.empty()) { @@ -11,6 +21,13 @@ ControllableVehicles::ControllableVehicles(const std::string& configFile) } } +ControllableVehicles::~ControllableVehicles() { + if (instance_ != nullptr) { + delete instance_; + instance_ = nullptr; + } +} + const std::vector& ControllableVehicles::getVehicles() const { return vehicles_; } @@ -26,7 +43,7 @@ const ControllableVehicleConfig* ControllableVehicles::findVehicle(const std::st bool ControllableVehicles::isControllable(const std::string& vehicleNo) const { // 查找车辆配置 - const auto* config = findVehicle(vehicleNo); + auto* config = findVehicle(vehicleNo); if (!config) { return false; } @@ -34,13 +51,14 @@ bool ControllableVehicles::isControllable(const std::string& vehicleNo) const { return config->type == "UNMANNED"; } -void ControllableVehicles::loadConfig(const std::string& configFile) { - std::ifstream file(configFile); - if (!file.is_open()) { - throw std::runtime_error("Failed to open controllable vehicles config file: " + configFile); - } - +bool ControllableVehicles::loadConfig(const std::string& configFile) { try { + std::ifstream file(configFile); + if (!file.is_open()) { + Logger::error("Failed to open controllable vehicles config file: ", configFile); + return false; + } + nlohmann::json jsonConfig; file >> jsonConfig; @@ -55,12 +73,14 @@ void ControllableVehicles::loadConfig(const std::string& configFile) { } Logger::info("Loaded ", vehicles_.size(), " controllable vehicles"); + return true; } catch (const std::exception& e) { - throw std::runtime_error("Failed to parse controllable vehicles config: " + std::string(e.what())); + Logger::error("Failed to parse controllable vehicles config: ", e.what()); + return false; } } -bool ControllableVehicles::sendCommand(const std::string& vehicleNo, const VehicleCommand& command) const { +bool ControllableVehicles::sendCommand(const std::string& vehicleNo, const VehicleCommand& command) { auto vehicle = findVehicle(vehicleNo); if (!vehicle) { Logger::error("Vehicle ", vehicleNo, " not found in controllable vehicles"); diff --git a/src/vehicle/ControllableVehicles.h b/src/vehicle/ControllableVehicles.h index cbed14c..d789bbd 100644 --- a/src/vehicle/ControllableVehicles.h +++ b/src/vehicle/ControllableVehicles.h @@ -14,24 +14,21 @@ struct ControllableVehicleConfig { }; class ControllableVehicles { -public: - explicit ControllableVehicles(const std::string& configFile); - virtual ~ControllableVehicles() = default; - - // 获取所有可控车辆配置 - const std::vector& getVehicles() const; - - // 根据车牌号查找可控车辆配置 - const ControllableVehicleConfig* findVehicle(const std::string& vehicleNo) const; - - // 检查车辆是否可控 - virtual bool isControllable(const std::string& vehicleNo) const; - - // 发送控制命令,返回是否发送成功 - virtual bool sendCommand(const std::string& vehicleNo, const VehicleCommand& command) const; - private: + static ControllableVehicles* instance_; + ControllableVehicles(const std::string& configFile); + ControllableVehicles(const ControllableVehicles&) = delete; + ControllableVehicles& operator=(const ControllableVehicles&) = delete; + ~ControllableVehicles(); + std::vector vehicles_; std::unique_ptr http_client_; - void loadConfig(const std::string& configFile); + bool loadConfig(const std::string& configFile); + +public: + static ControllableVehicles& getInstance(); + const std::vector& getVehicles() const; + const ControllableVehicleConfig* findVehicle(const std::string& vehicleNo) const; + bool isControllable(const std::string& vehicleNo) const; + bool sendCommand(const std::string& vehicleNo, const VehicleCommand& command); }; \ No newline at end of file diff --git a/tests/BasicCollisionTest.cpp b/tests/BasicCollisionTest.cpp index 1b4500b..1241041 100644 --- a/tests/BasicCollisionTest.cpp +++ b/tests/BasicCollisionTest.cpp @@ -1,15 +1,26 @@ -#include "detector/CollisionDetector.h" -#include "vehicle/ControllableVehicles.h" -#include "config/AirportBounds.h" #include #include +#include + +#include "detector/CollisionDetector.h" +#include "vehicle/ControllableVehicles.h" #include "utils/Logger.h" +#include "config/SystemConfig.h" +#include "config/AirportBounds.h" // Mock ControllableVehicles 类 -class MockControllableVehicles : public ControllableVehicles { +class MockControllableVehicles { public: - MockControllableVehicles() : ControllableVehicles("") {} - MOCK_CONST_METHOD1(isControllable, bool(const std::string& vehicleNo)); + MockControllableVehicles() = default; + + MOCK_METHOD(bool, isControllable, (const std::string& vehicleNo), (const)); + MOCK_METHOD(const ControllableVehicleConfig*, findVehicle, (const std::string& vehicleNo), (const)); + MOCK_METHOD(void, sendCommand, (const std::string& vehicleNo, const VehicleCommand& cmd)); + + // 转换为 ControllableVehicles& 的操作符 + operator const ControllableVehicles&() const { + return ControllableVehicles::getInstance(); + } }; // Mock AirportBounds 类 @@ -33,7 +44,7 @@ public: system_config.collision_detection.prediction.time_window = 30.0; // 设置预测时间窗口为30秒 } - MOCK_CONST_METHOD1(getAreaType, AreaType(const Vector2D& position)); + MOCK_METHOD(AreaType, getAreaType, (const Vector2D& position), (const)); const AreaConfig& getAreaConfig(AreaType type) const override { auto it = areaConfigs_.find(type); @@ -56,6 +67,10 @@ protected: EXPECT_CALL(*airportBounds_, getAreaType(::testing::_)) .WillRepeatedly(::testing::Return(AreaType::TEST_ZONE)); + // 设置 Mock ControllableVehicles 的行为 + EXPECT_CALL(*mockControllableVehicles_, isControllable(::testing::_)) + .WillRepeatedly(::testing::Return(true)); + detector_ = std::make_unique(*airportBounds_, *mockControllableVehicles_); } @@ -165,7 +180,7 @@ TEST_F(BasicCollisionTest, ParallelMotion) { auto result = detector_->checkCollision(v1, v2, 30.0); - EXPECT_FALSE(result.willCollide) << "平行运动且距离大于碰撞半径的物体不应该检测为碰��"; + EXPECT_FALSE(result.willCollide) << "平行运动且距离大于碰撞半径的物体不应该检测为碰撞"; EXPECT_EQ(result.type, CollisionType::PARALLEL) << "应该识别为平行运动"; // 增加更多验证 @@ -210,26 +225,26 @@ TEST_F(BasicCollisionTest, CrossingPaths) { // v2: 速度分量 (-2.588, 9.659) m/s // 10 m/s * (cos(75°), sin(75°)) // 相对速度: (-6.47, -4.83) m/s // 相对速度大小: 8.06 m/s - // 碰撞点在两车轨迹交点前的安全距离处 - double collision_time = 2.6; // 根据实际计算得到 - Vector2D collision_point = {126.68, 156.39}; // 两车位置的中点 + // 碰撞点在两车位置的中点 + double collision_time = 2.07; // 根据实际计算得到 + Vector2D collision_point = {126.34, 150.006}; // 两车位置的中点 - EXPECT_NEAR(result.timeToCollision, collision_time, 0.1) << "考虑碰撞半径25米,碰撞时间应该接近2.6秒"; - EXPECT_NEAR(result.collisionPoint.x, collision_point.x, 0.1) << "碰撞点x坐标应该在126.68"; - EXPECT_NEAR(result.collisionPoint.y, collision_point.y, 0.1) << "碰撞点y坐标应该在156.39"; + EXPECT_NEAR(result.timeToCollision, collision_time, 0.1) << "考虑碰撞半径25米,碰撞时间应该接近2.07秒"; + EXPECT_NEAR(result.collisionPoint.x, collision_point.x, 0.1) << "碰撞点x坐标应该在126.34"; + EXPECT_NEAR(result.collisionPoint.y, collision_point.y, 0.1) << "碰撞点y坐标应该在150.006"; // 增加更多验证 EXPECT_NEAR(result.minDistance, 50.0, 0.1) << "最小距离应该是碰撞半径之和50米"; EXPECT_NEAR(result.timeToMinDistance, collision_time, 0.1) << "最小距离时间应该等于碰撞时间"; // 验证物体状态 - EXPECT_NEAR(result.object1State.position.x, 110.09, 0.1); - EXPECT_NEAR(result.object1State.position.y, 137.67, 0.1); - EXPECT_DOUBLE_EQ(result.object1State.speed, 15.0); // 更新为正确的速度 + EXPECT_NEAR(result.object1State.position.x, 108.04, 0.1); + EXPECT_NEAR(result.object1State.position.y, 130.007, 0.1); + EXPECT_DOUBLE_EQ(result.object1State.speed, 15.0); EXPECT_DOUBLE_EQ(result.object1State.heading, 75.0); - EXPECT_NEAR(result.object2State.position.x, 143.27, 0.1); - EXPECT_NEAR(result.object2State.position.y, 175.11, 0.1); + EXPECT_NEAR(result.object2State.position.x, 144.64, 0.1); + EXPECT_NEAR(result.object2State.position.y, 170.005, 0.1); EXPECT_DOUBLE_EQ(result.object2State.speed, 10.0); EXPECT_DOUBLE_EQ(result.object2State.heading, 105.0); } @@ -257,17 +272,17 @@ TEST_F(BasicCollisionTest, PerpendicularCrossingPaths) { EXPECT_EQ(result.type, CollisionType::CROSSING) << "应该识别为交叉碰撞"; // 计算碰撞时间和位置: - // v1: 速度分量 (0.0, 10.0) m/s - // v2: 速度分量 (-10.0, 0.0) m/s + // v1: 速度分量 (10.0, 0.0) m/s + // v2: 速度分量 (0.0, -10.0) m/s // 相对速度: (-10.0, -10.0) m/s // 相对速度大小: 14.14 m/s - // 由于碰撞半径为 25m,实际碰撞会提前发生 - double collision_time = 1.46; // 根据实际计算得到 - Vector2D collision_point = {117.68, 132.32}; // 根据实际计算得到 + // 当前距离小于安全距离时,立即判定为碰撞 + double collision_time = 0.0; // 当前距离小于安全距离,立即碰撞 + Vector2D collision_point = {125.0, 125.0}; // 两车当前位置的中点 - EXPECT_NEAR(result.timeToCollision, collision_time, 0.1) << "考虑碰撞半径25米,碰时间应该接近1.46秒"; - EXPECT_NEAR(result.collisionPoint.x, collision_point.x, 0.1) << "碰撞点x坐标应该在117.68"; - EXPECT_NEAR(result.collisionPoint.y, collision_point.y, 0.1) << "碰撞点y坐标应该在132.32"; + EXPECT_NEAR(result.timeToCollision, collision_time, 0.1) << "当前距离小于安全距离,碰撞时间应该为0"; + EXPECT_NEAR(result.collisionPoint.x, collision_point.x, 0.1) << "碰撞点x坐标应该在125.0"; + EXPECT_NEAR(result.collisionPoint.y, collision_point.y, 0.1) << "碰撞点y坐标应该在125.0"; // 增加更多验证 EXPECT_NEAR(result.minDistance, 50.0, 0.1) << "最小距离应该是碰撞半径之和50米"; @@ -275,11 +290,11 @@ TEST_F(BasicCollisionTest, PerpendicularCrossingPaths) { // 验证物体状态 EXPECT_NEAR(result.object1State.position.x, 100.0, 0.1); - EXPECT_NEAR(result.object1State.position.y, 114.64, 0.1); + EXPECT_NEAR(result.object1State.position.y, 100.0, 0.1); EXPECT_DOUBLE_EQ(result.object1State.speed, 10.0); EXPECT_DOUBLE_EQ(result.object1State.heading, 90.0); - EXPECT_NEAR(result.object2State.position.x, 135.36, 0.1); + EXPECT_NEAR(result.object2State.position.x, 150.0, 0.1); EXPECT_NEAR(result.object2State.position.y, 150.0, 0.1); EXPECT_DOUBLE_EQ(result.object2State.speed, 10.0); EXPECT_DOUBLE_EQ(result.object2State.heading, 180.0); @@ -486,7 +501,7 @@ TEST_F(BasicCollisionTest, CrossingBeforeAndAfter) { // 3. 测试交叉后的情况 // 航空器已经通过交叉点并远离安全距离,无人车还在交叉点附近 - aircraft.position = {crossPoint.x + 120.0, crossPoint.y}; // 航空器在交叉点东侧120米 + aircraft.position = {crossPoint.x + 160.0, crossPoint.y}; // 航空器在交叉点东侧160米(大于安全距离150米) vehicle.position = {crossPoint.x, crossPoint.y - 10.0}; // 无人车还在交叉点附近 // 更新交通数据 @@ -504,7 +519,7 @@ TEST_F(BasicCollisionTest, CrossingBeforeAndAfter) { EXPECT_TRUE(risks.empty()) << "航空器通过远离安全距离后,应该解除冲突"; - // 4. 测试无���车继续运动 + // 4. 测试无人车继续运动 // 无人车向北移动到交叉点 vehicle.position = {crossPoint.x, crossPoint.y}; diff --git a/tests/CollisionDetectorTest.cpp b/tests/CollisionDetectorTest.cpp index 47871e1..6fcf5f9 100644 --- a/tests/CollisionDetectorTest.cpp +++ b/tests/CollisionDetectorTest.cpp @@ -8,10 +8,18 @@ #include // Mock ControllableVehicles 类 -class MockControllableVehicles : public ControllableVehicles { +class MockControllableVehicles { public: - MockControllableVehicles() : ControllableVehicles("") {} // 使用空字符串,避免加载实际配置 - MOCK_CONST_METHOD1(isControllable, bool(const std::string& vehicleNo)); + MockControllableVehicles() = default; + + MOCK_METHOD(bool, isControllable, (const std::string& vehicleNo), (const)); + MOCK_METHOD(const ControllableVehicleConfig*, findVehicle, (const std::string& vehicleNo), (const)); + MOCK_METHOD(void, sendCommand, (const std::string& vehicleNo, const VehicleCommand& cmd)); + + // 转换为 ControllableVehicles& 的操作符 + operator const ControllableVehicles&() const { + return ControllableVehicles::getInstance(); + } }; // Mock AirportBounds 类 @@ -199,7 +207,7 @@ TEST_F(CollisionDetectorTest, PerpendicularCrossingPathsCollision) { EXPECT_TRUE(collisionResult.willCollide) << "垂直交叉路径的车辆应该检测到碰撞"; // 测试2:不同速度比 - v1.speed = 5.0; // 降���速度 + v1.speed = 5.0; // 降低速度 v2.speed = 15.0; // 提高速度 collisionResult = detector_->checkCollision(v1, v2, 30.0); EXPECT_TRUE(collisionResult.willCollide) << "不同速度的垂直交叉路径车辆应该检测到碰撞"; @@ -265,7 +273,7 @@ TEST_F(CollisionDetectorTest, TailgatingCollision) { v2.type = MovingObjectType::UNMANNED; v2.isControllable = true; - // 测试1:同向��速 + // 测试1:同向同速 auto collisionResult = detector_->checkCollision(v1, v2, 30.0); EXPECT_FALSE(collisionResult.willCollide) << "同向同速的车辆不应该检测到碰撞"; diff --git a/tests/DataCollectorTest.cpp b/tests/DataCollectorTest.cpp index beebd76..31f37c6 100644 --- a/tests/DataCollectorTest.cpp +++ b/tests/DataCollectorTest.cpp @@ -11,9 +11,11 @@ public: MOCK_METHOD0(connect, bool()); MOCK_METHOD0(disconnect, void()); MOCK_CONST_METHOD0(isAvailable, bool()); - MOCK_METHOD1(fetchAircraftData, bool(std::vector&)); - MOCK_METHOD1(fetchVehicleData, bool(std::vector&)); + MOCK_METHOD1(fetchPositionAircraftData, bool(std::vector&)); + MOCK_METHOD1(fetchPositionVehicleData, bool(std::vector&)); MOCK_METHOD1(fetchTrafficLightSignals, bool(std::vector&)); + MOCK_METHOD2(sendUnmannedVehicleCommand, bool(const std::string&, const VehicleCommand&)); + MOCK_METHOD2(fetchUnmannedVehicleStatus, bool(const std::string&, std::string&)); }; class DataCollectorTest : public ::testing::Test { @@ -70,9 +72,14 @@ protected: // 测试初始化 TEST_F(DataCollectorTest, Initialization) { DataSourceConfig dataSourceConfig; - dataSourceConfig.host = "localhost"; - dataSourceConfig.port = 8080; - dataSourceConfig.aircraft_path = "/api/getCurrentFlightPositions"; + + // 设置位置数据配置 + dataSourceConfig.position.host = "localhost"; + dataSourceConfig.position.port = 8080; + dataSourceConfig.position.aircraft_path = "/api/getCurrentFlightPositions"; + dataSourceConfig.position.refresh_interval_ms = 1000; + dataSourceConfig.position.timeout_ms = 5000; + dataSourceConfig.position.read_timeout_ms = 1000; WarnConfig warnConfig; warnConfig.warning_interval_ms = 1000; @@ -94,13 +101,13 @@ TEST_F(DataCollectorTest, RefreshTest) { }; // 设置 Mock 数据返回 - EXPECT_CALL(*mockSource, fetchAircraftData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionAircraftData(::testing::_)) .WillOnce(::testing::DoAll( ::testing::SetArgReferee<0>(testAircraft), ::testing::Return(true) )); - EXPECT_CALL(*mockSource, fetchVehicleData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionVehicleData(::testing::_)) .WillOnce(::testing::DoAll( ::testing::SetArgReferee<0>(testVehicles), ::testing::Return(true) @@ -136,13 +143,13 @@ TEST_F(DataCollectorTest, DataCollectionLoop) { }; // 设置 Mock 数据返回 - EXPECT_CALL(*mockSource, fetchAircraftData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionAircraftData(::testing::_)) .WillRepeatedly(::testing::DoAll( ::testing::SetArgReferee<0>(testAircraft), ::testing::Return(true) )); - EXPECT_CALL(*mockSource, fetchVehicleData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionVehicleData(::testing::_)) .WillRepeatedly(::testing::DoAll( ::testing::SetArgReferee<0>(testVehicles), ::testing::Return(true) @@ -168,9 +175,9 @@ TEST_F(DataCollectorTest, DataCollectionLoop) { // 测试错误处理 TEST_F(DataCollectorTest, ErrorHandling) { // 设置 Mock 返回错误 - EXPECT_CALL(*mockSource, fetchAircraftData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionAircraftData(::testing::_)) .WillOnce(::testing::Return(false)); - EXPECT_CALL(*mockSource, fetchVehicleData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionVehicleData(::testing::_)) .WillOnce(::testing::Return(false)); // 执行刷新 @@ -230,10 +237,13 @@ TEST_F(DataCollectorTest, TrafficLightSignalsErrorTest) { // 测试连接健康检查和超时告警 TEST_F(DataCollectorTest, ConnectionHealthAndTimeout) { DataSourceConfig dataSourceConfig; - dataSourceConfig.host = "localhost"; - dataSourceConfig.port = 8080; - dataSourceConfig.timeout_ms = 1000; // 1秒超时 - dataSourceConfig.refresh_interval_ms = 100; // 100ms刷新间隔 + + // 设置位置数据配置 + dataSourceConfig.position.host = "localhost"; + dataSourceConfig.position.port = 8080; + dataSourceConfig.position.timeout_ms = 1000; // 1秒超时 + dataSourceConfig.position.read_timeout_ms = 500; // 0.5秒读取超时 + dataSourceConfig.position.refresh_interval_ms = 100; // 100ms刷新间隔 WarnConfig warnConfig; warnConfig.warning_interval_ms = 500; // 500ms告警间隔 @@ -245,9 +255,9 @@ TEST_F(DataCollectorTest, ConnectionHealthAndTimeout) { .WillRepeatedly(::testing::Return(false)); // 模拟数据获取失败 - EXPECT_CALL(*mockSource, fetchAircraftData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionAircraftData(::testing::_)) .WillRepeatedly(::testing::Return(false)); - EXPECT_CALL(*mockSource, fetchVehicleData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionVehicleData(::testing::_)) .WillRepeatedly(::testing::Return(false)); // 启动采集 @@ -269,9 +279,13 @@ TEST_F(DataCollectorTest, ConnectionHealthAndTimeout) { // 测试连接恢复 TEST_F(DataCollectorTest, ConnectionRecovery) { DataSourceConfig config; - config.host = "localhost"; - config.port = 8080; - config.refresh_interval_ms = 10; + + // 设置位置数据配置 + config.position.host = "localhost"; + config.position.port = 8080; + config.position.refresh_interval_ms = 10; + config.position.timeout_ms = 1000; + config.position.read_timeout_ms = 500; WarnConfig warnConfig; warnConfig.warning_interval_ms = 20; @@ -283,14 +297,14 @@ TEST_F(DataCollectorTest, ConnectionRecovery) { }; // 移除 InSequence,直接设置期望 - EXPECT_CALL(*mockSource, fetchAircraftData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionAircraftData(::testing::_)) .WillOnce(::testing::Return(false)) .WillOnce(::testing::DoAll( ::testing::SetArgReferee<0>(testAircraft), ::testing::Return(true) )); - // 行两次刷新 + // 执行两次刷新 collector->refresh(); // 第一次失败 collector->refresh(); // 第二次成功 @@ -305,9 +319,13 @@ TEST_F(DataCollectorTest, ConnectionRecovery) { // 测试长连接下的数据获取 TEST_F(DataCollectorTest, LongConnectionDataFetch) { DataSourceConfig dataSourceConfig; - dataSourceConfig.host = "localhost"; - dataSourceConfig.port = 8080; - dataSourceConfig.refresh_interval_ms = 100; + + // 设置位置数据配置 + dataSourceConfig.position.host = "localhost"; + dataSourceConfig.position.port = 8080; + dataSourceConfig.position.refresh_interval_ms = 100; + dataSourceConfig.position.timeout_ms = 1000; + dataSourceConfig.position.read_timeout_ms = 500; collector->initialize(dataSourceConfig, WarnConfig{}); @@ -315,23 +333,52 @@ TEST_F(DataCollectorTest, LongConnectionDataFetch) { createTestAircraft("TEST1", 36.36, 120.08) }; + std::vector testVehicles = { + createTestVehicle("VEH1", 36.36, 120.08) + }; + + std::vector testSignals = { + createTestTrafficLight("TL001", 0) + }; + // 模拟连接保持可用 EXPECT_CALL(*mockSource, isAvailable()) .WillRepeatedly(::testing::Return(true)); // 模拟多次成功获取数据 - EXPECT_CALL(*mockSource, fetchAircraftData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionAircraftData(::testing::_)) .Times(::testing::AtLeast(3)) .WillRepeatedly(::testing::DoAll( ::testing::SetArgReferee<0>(testAircraft), ::testing::Return(true) )); + + // 添加其他数据源的 mock 行为 + EXPECT_CALL(*mockSource, fetchPositionVehicleData(::testing::_)) + .WillRepeatedly(::testing::DoAll( + ::testing::SetArgReferee<0>(testVehicles), + ::testing::Return(true) + )); + + EXPECT_CALL(*mockSource, fetchTrafficLightSignals(::testing::_)) + .WillRepeatedly(::testing::DoAll( + ::testing::SetArgReferee<0>(testSignals), + ::testing::Return(true) + )); + + // 添加无人车状态获取的 mock 行为 + std::string testStatus = "NORMAL"; + EXPECT_CALL(*mockSource, fetchUnmannedVehicleStatus(::testing::_, ::testing::_)) + .WillRepeatedly(::testing::DoAll( + ::testing::SetArgReferee<1>(testStatus), + ::testing::Return(true) + )); // 启动采集 collector->start(); // 等待多个刷新周期 - std::this_thread::sleep_for(std::chrono::milliseconds(350)); // 应该执行至少3次获取 + std::this_thread::sleep_for(std::chrono::milliseconds(500)); // 增加等待时间确保执行次数 // 验证数据 auto aircraft = collector->getAircraftData(); @@ -340,17 +387,31 @@ TEST_F(DataCollectorTest, LongConnectionDataFetch) { EXPECT_EQ(aircraft[0].flightNo, "TEST1"); } + auto vehicles = collector->getVehicleData(); + EXPECT_FALSE(vehicles.empty()); + if (!vehicles.empty()) { + EXPECT_EQ(vehicles[0].vehicleNo, "VEH1"); + } + + auto signals = collector->getTrafficLightSignals(); + EXPECT_FALSE(signals.empty()); + if (!signals.empty()) { + EXPECT_EQ(signals[0].trafficLightId, "TL001"); + } + // 停止采集 collector->stop(); } TEST_F(DataCollectorTest, InitializeWithTimeoutConfig) { DataSourceConfig config; - config.host = "localhost"; - config.port = 8080; - config.timeout_ms = 5000; // 连接超时 5 秒 - config.read_timeout_ms = 2000; // 读取超时 2 秒 - config.refresh_interval_ms = 100; + + // 设置位置数据配置 + config.position.host = "localhost"; + config.position.port = 8080; + config.position.timeout_ms = 5000; // 连接超时 5 秒 + config.position.read_timeout_ms = 2000; // 读取超时 2 秒 + config.position.refresh_interval_ms = 100; WarnConfig warnConfig; warnConfig.warning_interval_ms = 500; @@ -360,11 +421,13 @@ TEST_F(DataCollectorTest, InitializeWithTimeoutConfig) { TEST_F(DataCollectorTest, TimeoutWarningTest) { DataSourceConfig config; - config.host = "localhost"; - config.port = 8080; - config.timeout_ms = 1000; // 连接超时 1 秒 - config.read_timeout_ms = 500; // 读取超时 0.5 秒 - config.refresh_interval_ms = 100; + + // 设置位置数据配置 + config.position.host = "localhost"; + config.position.port = 8080; + config.position.timeout_ms = 1000; // 连接超时 1 秒 + config.position.read_timeout_ms = 500; // 读取超时 0.5 秒 + config.position.refresh_interval_ms = 100; WarnConfig warnConfig; warnConfig.warning_interval_ms = 200; // 警告间隔 0.2 秒 @@ -375,7 +438,7 @@ TEST_F(DataCollectorTest, TimeoutWarningTest) { EXPECT_CALL(*mockSource, isAvailable()) .WillRepeatedly(::testing::Return(true)); - EXPECT_CALL(*mockSource, fetchAircraftData(::testing::_)) + EXPECT_CALL(*mockSource, fetchPositionAircraftData(::testing::_)) .WillRepeatedly(::testing::Return(false)); // 持续读取超时 // 启动采集 @@ -391,11 +454,13 @@ TEST_F(DataCollectorTest, TimeoutWarningTest) { // 测试超时警告机制 TEST_F(DataCollectorTest, TimeoutWarningMechanism) { DataSourceConfig config; - config.host = "localhost"; - config.port = 8080; - config.timeout_ms = 200; // 连接超时 200ms - config.read_timeout_ms = 100; // 读取超时 100ms - config.refresh_interval_ms = 10; + + // 设置位置数据配置 + config.position.host = "localhost"; + config.position.port = 8080; + config.position.timeout_ms = 200; // 连接超时 200ms + config.position.read_timeout_ms = 100; // 读取超时 100ms + config.position.refresh_interval_ms = 10; WarnConfig warnConfig; warnConfig.warning_interval_ms = 50; // 警告间隔 50ms @@ -416,9 +481,12 @@ TEST_F(DataCollectorTest, TimeoutWarningMechanism) { .WillRepeatedly(::testing::Invoke([&warningCount](const network::TimeoutWarningMessage& warning) { warningCount++; // 验证警告消息的内容 - EXPECT_EQ(warning.source, "data_source"); + EXPECT_THAT(warning.source, ::testing::AnyOf( + ::testing::StrEq("position"), + ::testing::StrEq("unmanned"), + ::testing::StrEq("traffic_light") + )); EXPECT_GT(warning.elapsed_ms, 0); - // 不检查具体的超时类型,因为这取决于实际的时间流逝 })); // 设置 mock system 到 collector @@ -428,12 +496,17 @@ TEST_F(DataCollectorTest, TimeoutWarningMechanism) { // 启动采集器 collector->start(); - // 模拟数据获取失败 - EXPECT_CALL(*mockSource, fetchAircraftData(::testing::_)) + // 模拟所有数据源获取失败 + EXPECT_CALL(*mockSource, fetchPositionAircraftData(::testing::_)) + .WillRepeatedly(::testing::Return(false)); + + EXPECT_CALL(*mockSource, fetchPositionVehicleData(::testing::_)) + .WillRepeatedly(::testing::Return(false)); + + EXPECT_CALL(*mockSource, fetchTrafficLightSignals(::testing::_)) .WillRepeatedly(::testing::Return(false)); // 等待足够长的时间以确保警告被发送 - // 等待时间应该超过 refresh_interval_ms + timeout_ms + warning_interval_ms std::this_thread::sleep_for(std::chrono::milliseconds(300)); // 停止采集器 @@ -446,11 +519,13 @@ TEST_F(DataCollectorTest, TimeoutWarningMechanism) { // 测试读取超时机制 TEST_F(DataCollectorTest, ReadTimeoutMechanism) { DataSourceConfig config; - config.host = "localhost"; - config.port = 8080; - config.timeout_ms = 100; // 连接超时 100ms - config.read_timeout_ms = 50; // 读取超时 50ms - config.refresh_interval_ms = 10; + + // 设置位置数据配置 + config.position.host = "localhost"; + config.position.port = 8080; + config.position.timeout_ms = 100; // 连接超时 100ms + config.position.read_timeout_ms = 50; // 读取超时 50ms + config.position.refresh_interval_ms = 10; WarnConfig warnConfig; warnConfig.warning_interval_ms = 20; // 警告间隔 20ms @@ -471,7 +546,11 @@ TEST_F(DataCollectorTest, ReadTimeoutMechanism) { .WillRepeatedly(::testing::Invoke([&warningCount](const network::TimeoutWarningMessage& warning) { warningCount++; // 验证警告消息的内容 - EXPECT_EQ(warning.source, "data_source"); + EXPECT_THAT(warning.source, ::testing::AnyOf( + ::testing::StrEq("position"), + ::testing::StrEq("unmanned"), + ::testing::StrEq("traffic_light") + )); EXPECT_GT(warning.elapsed_ms, 0); EXPECT_TRUE(warning.is_read_timeout); // 标记为读取超时 })); @@ -483,16 +562,27 @@ TEST_F(DataCollectorTest, ReadTimeoutMechanism) { // 启动采集器 collector->start(); - // 模拟读取超时 - EXPECT_CALL(*mockSource, fetchAircraftData(::testing::_)) + // 模拟所有数据源读取超时 + EXPECT_CALL(*mockSource, fetchPositionAircraftData(::testing::_)) .WillRepeatedly(::testing::Invoke([](std::vector& aircraft) { std::this_thread::sleep_for(std::chrono::milliseconds(60)); // 睡眠超过读取超时时间但小于连接超时 return false; })); + + EXPECT_CALL(*mockSource, fetchPositionVehicleData(::testing::_)) + .WillRepeatedly(::testing::Invoke([](std::vector& vehicles) { + std::this_thread::sleep_for(std::chrono::milliseconds(60)); + return false; + })); + + EXPECT_CALL(*mockSource, fetchTrafficLightSignals(::testing::_)) + .WillRepeatedly(::testing::Invoke([](std::vector& signals) { + std::this_thread::sleep_for(std::chrono::milliseconds(60)); + return false; + })); // 等待足够长的时间以确保警告被发送 - // 等待时间应该超过 refresh_interval_ms + read_timeout_ms + warning_interval_ms - std::this_thread::sleep_for(std::chrono::milliseconds(200)); + std::this_thread::sleep_for(std::chrono::milliseconds(300)); // 停止采集器 collector->stop(); diff --git a/tests/HTTPDataSourceTest.cpp b/tests/HTTPDataSourceTest.cpp index a25d29b..7c1e16c 100644 --- a/tests/HTTPDataSourceTest.cpp +++ b/tests/HTTPDataSourceTest.cpp @@ -1,214 +1,247 @@ +#include "network/HTTPDataSource.h" #include #include -#include "network/HTTPDataSource.h" #include "utils/Logger.h" +#include +#include +#include class HTTPDataSourceTest : public ::testing::Test { protected: - std::unique_ptr source; - - void SetUp() override { - DataSourceConfig config; - config.host = "localhost"; - config.port = 8081; - config.aircraft_path = "/api/getCurrentFlightPositions"; - config.vehicle_path = "/api/getCurrentVehiclePositions"; - config.traffic_light_path = "/api/getTrafficLightSignals"; - source = std::make_unique(config); - } - - void TearDown() override { - source.reset(); - } + void SetUp() override {} + void TearDown() override {} }; -TEST_F(HTTPDataSourceTest, ConnectTest) { - EXPECT_FALSE(source->isAvailable()); // 初始状态应该是未连接 - EXPECT_TRUE(source->connect()); // 连接应该成功 - EXPECT_TRUE(source->isAvailable()); // 连接后应该可用 -} - -TEST_F(HTTPDataSourceTest, DisconnectTest) { - source->connect(); - EXPECT_TRUE(source->isAvailable()); - source->disconnect(); - EXPECT_FALSE(source->isAvailable()); -} - -TEST_F(HTTPDataSourceTest, FetchAircraftDataTest) { +TEST_F(HTTPDataSourceTest, BasicFunctionality) { + DataSourceConfig config; + config.position.host = "localhost"; + config.position.port = 8081; + config.position.aircraft_path = "/openApi/getCurrentFlightPositions"; + config.position.vehicle_path = "/openApi/getCurrentVehiclePositions"; + config.position.auth.auth_required = true; + config.position.auth.auth_path = "/login"; + config.position.auth.username = "dianxin"; + config.position.auth.password = "dianxin@123"; + config.position.timeout_ms = 5000; + config.position.read_timeout_ms = 2000; + config.position.refresh_interval_ms = 100; + + HTTPDataSource source(config); + ASSERT_TRUE(source.connect()) << "连接失败"; + std::vector aircraft; + bool success = source.fetchPositionAircraftData(aircraft); + ASSERT_TRUE(success) << "获取航空器数据失败"; + ASSERT_FALSE(aircraft.empty()) << "航空器数据为空"; - // 尝试连接 - bool connected = source->connect(); - Logger::info("Connection result: ", connected ? "success" : "failed"); - EXPECT_TRUE(connected); - - // 检查连接状态 - bool available = source->isAvailable(); - Logger::info("Connection available: ", available ? "yes" : "no"); - EXPECT_TRUE(available); - - // 获取数据 - bool fetchResult = source->fetchAircraftData(aircraft); - Logger::info("Fetch result: ", fetchResult ? "success" : "failed"); - EXPECT_TRUE(fetchResult); - - // 检查数据 - Logger::info("Aircraft data size: ", aircraft.size()); - EXPECT_FALSE(aircraft.empty()); -} - -TEST_F(HTTPDataSourceTest, FetchVehicleDataTest) { std::vector vehicles; - EXPECT_TRUE(source->connect()); // 确保连接成功 - EXPECT_TRUE(source->fetchVehicleData(vehicles)); - EXPECT_FALSE(vehicles.empty()); + ASSERT_TRUE(source.fetchPositionVehicleData(vehicles)) << "获取车辆数据失败"; + ASSERT_FALSE(vehicles.empty()) << "车辆数据为空"; } -TEST_F(HTTPDataSourceTest, FetchTrafficLightSignalsTest) { - std::vector signals; - EXPECT_TRUE(source->connect()); // 确保连接成功 - EXPECT_TRUE(source->fetchTrafficLightSignals(signals)); - EXPECT_FALSE(signals.empty()); -} - -TEST_F(HTTPDataSourceTest, CustomPathTest) { - // 测试使用自定义路径创建数据源 - DataSourceConfig config; - config.host = "localhost"; - config.port = 8081; - config.aircraft_path = "/custom/path"; - auto customSource = std::make_unique(config); - EXPECT_TRUE(customSource->connect()); - EXPECT_TRUE(customSource->isAvailable()); -} - -TEST_F(HTTPDataSourceTest, ConnectionFailureTest) { - // 测试连接到不存在的服务器 - DataSourceConfig config; - config.host = "localhost"; // 使用本地地址 - config.port = 1; // 使用一个通常不会被使用的端口 - auto invalidSource = std::make_unique(config); - EXPECT_FALSE(invalidSource->connect()); - EXPECT_FALSE(invalidSource->isAvailable()); -} - -TEST_F(HTTPDataSourceTest, FetchDataWithoutConnectionTest) { - // 测试在未连接状态下获取数据 - std::vector aircraft; - std::vector vehicles; +TEST_F(HTTPDataSourceTest, AuthenticationFailure) { + DataSourceConfig config; + config.position.host = "localhost"; + config.position.port = 8081; + config.position.aircraft_path = "/openApi/getCurrentFlightPositions"; + config.position.vehicle_path = "/openApi/getCurrentVehiclePositions"; + config.position.refresh_interval_ms = 1000; + config.position.timeout_ms = 1000; + config.position.read_timeout_ms = 500; + + config.position.auth.auth_required = true; + config.position.auth.username = "wrong_user"; + config.position.auth.password = "wrong_pass"; + config.position.auth.auth_path = "/login"; + + HTTPDataSource source(config); + std::vector aircraft; + EXPECT_FALSE(source.fetchPositionAircraftData(aircraft)); +} + +TEST_F(HTTPDataSourceTest, Reconnection) { + DataSourceConfig config; + config.position.host = "localhost"; + config.position.port = 8081; + config.position.aircraft_path = "/openApi/getCurrentFlightPositions"; + config.position.vehicle_path = "/openApi/getCurrentVehiclePositions"; + config.position.refresh_interval_ms = 1000; + config.position.timeout_ms = 1000; + config.position.read_timeout_ms = 500; + + config.position.auth.auth_required = true; + config.position.auth.username = "dianxin"; + config.position.auth.password = "dianxin@123"; + config.position.auth.auth_path = "/login"; + + HTTPDataSource source(config); + EXPECT_TRUE(source.connect()); + + std::vector aircraft; + EXPECT_TRUE(source.fetchPositionAircraftData(aircraft)); + + source.disconnect(); + EXPECT_TRUE(source.connect()); + + aircraft.clear(); + EXPECT_TRUE(source.fetchPositionAircraftData(aircraft)); +} + +TEST_F(HTTPDataSourceTest, AuthenticationOnly) { + DataSourceConfig config; + config.position.host = "localhost"; + config.position.port = 8081; + config.position.aircraft_path = "/openApi/getCurrentFlightPositions"; + config.position.vehicle_path = "/openApi/getCurrentVehiclePositions"; + config.position.refresh_interval_ms = 1000; + config.position.timeout_ms = 1000; + config.position.read_timeout_ms = 500; + + config.position.auth.auth_required = true; + config.position.auth.username = "dianxin"; + config.position.auth.password = "dianxin@123"; + config.position.auth.auth_path = "/login"; + + HTTPDataSource source(config); + EXPECT_TRUE(source.connect()); + + std::vector aircraft; + EXPECT_TRUE(source.fetchPositionAircraftData(aircraft)); +} + +TEST_F(HTTPDataSourceTest, TrafficLightSignals) { + DataSourceConfig config; + config.position.host = "localhost"; + config.position.port = 8081; + config.traffic_light.host = "localhost"; + config.traffic_light.port = 8081; + config.traffic_light.signal_path = "/api/VehicleCommandInfo"; + config.vehicle.host = "localhost"; + config.vehicle.port = 8081; + config.vehicle.command_path = "/api/VehicleCommandInfo"; + + HTTPDataSource source(config); + ASSERT_TRUE(source.connect()); + + // 先发送 GREEN 指令解除 RED 状态 + VehicleCommand green_command; + green_command.vehicleId = "QN001"; + green_command.type = CommandType::SIGNAL; + green_command.reason = CommandReason::TRAFFIC_LIGHT; + green_command.signalState = SignalState::GREEN; + green_command.intersectionId = "INTERSECTION_001"; + green_command.timestamp = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count(); + ASSERT_TRUE(source.sendUnmannedVehicleCommand(green_command.vehicleId, green_command)) << "发送绿灯指令失败"; + + // 等待一小段时间确保 GREEN 指令生效 + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + + // 再发送 RESUME 指令解除其他可能的状态 + VehicleCommand resume_command; + resume_command.vehicleId = "QN001"; + resume_command.type = CommandType::RESUME; + resume_command.reason = CommandReason::RESUME_TRAFFIC; + resume_command.timestamp = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count(); + ASSERT_TRUE(source.sendUnmannedVehicleCommand(resume_command.vehicleId, resume_command)) << "发送恢复指令失败"; + + // 等待一小段时间确保 RESUME 指令生效 + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + + // 发送红绿灯信号指令 + VehicleCommand command; + command.vehicleId = "QN001"; + command.type = CommandType::SIGNAL; + command.reason = CommandReason::TRAFFIC_LIGHT; + command.signalState = SignalState::RED; + command.intersectionId = "INTERSECTION_001"; + command.latitude = 36.36; + command.longitude = 120.08; + command.timestamp = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count(); + + ASSERT_TRUE(source.sendUnmannedVehicleCommand(command.vehicleId, command)) << "获取红绿灯信号失败"; +} + +TEST_F(HTTPDataSourceTest, UnmannedVehicleCommand) { + DataSourceConfig config; + config.vehicle.host = "localhost"; + config.vehicle.port = 8081; + config.vehicle.command_path = "/api/VehicleCommandInfo"; + + HTTPDataSource source(config); + ASSERT_TRUE(source.connect()); + + // 先发送 GREEN 指令解除 RED 状态 + VehicleCommand green_command; + green_command.vehicleId = "QN001"; + green_command.type = CommandType::SIGNAL; + green_command.reason = CommandReason::TRAFFIC_LIGHT; + green_command.signalState = SignalState::GREEN; + green_command.intersectionId = "INTERSECTION_001"; + green_command.timestamp = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count(); + ASSERT_TRUE(source.sendUnmannedVehicleCommand(green_command.vehicleId, green_command)) << "发送绿灯指令失败"; + + // 等待一小段时间确保 GREEN 指令生效 + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + + // 再发送 RESUME 指令解除其他可能的状态 + VehicleCommand resume_command; + resume_command.vehicleId = "QN001"; + resume_command.type = CommandType::RESUME; + resume_command.reason = CommandReason::RESUME_TRAFFIC; + resume_command.timestamp = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count(); + ASSERT_TRUE(source.sendUnmannedVehicleCommand(resume_command.vehicleId, resume_command)) << "发送恢复指令失败"; + + // 等待一小段时间确保 RESUME 指令生效 + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + + // 发送告警指令 + VehicleCommand command; + command.vehicleId = "QN001"; + command.type = CommandType::ALERT; + command.reason = CommandReason::AIRCRAFT_CROSSING; + command.relativeSpeed = 100; + command.relativeMotionX = 100; + command.relativeMotionY = 100; + command.minDistance = 100; + command.latitude = 36.36; + command.longitude = 120.08; + command.timestamp = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count(); + + ASSERT_TRUE(source.sendUnmannedVehicleCommand(command.vehicleId, command)) << "发送无人车指令失败"; +} + +TEST_F(HTTPDataSourceTest, TrafficLightAndUnmannedAuthFailure) { + DataSourceConfig config; + config.traffic_light.host = "localhost"; + config.traffic_light.port = 8081; + config.traffic_light.signal_path = "/api/VehicleCommandInfo"; + config.traffic_light.auth.auth_required = true; + config.traffic_light.auth.username = "wrong_user"; + config.traffic_light.auth.password = "wrong_pass"; + + config.vehicle.host = "localhost"; + config.vehicle.port = 8081; + config.vehicle.command_path = "/api/VehicleCommandInfo"; + config.vehicle.auth.auth_required = true; + config.vehicle.auth.username = "wrong_user"; + config.vehicle.auth.password = "wrong_pass"; + + HTTPDataSource source(config); + std::vector signals; + EXPECT_FALSE(source.fetchTrafficLightSignals(signals)); - // 配置一个很短的刷新间隔,这样重连会快速失败 - DataSourceConfig config; - config.host = "localhost"; - config.port = 1; // 使用一个通常不会被使用的端口 - config.refresh_interval_ms = 1; // 设置很短的刷新间隔 - source = std::make_unique(config); - - // 测试所有数据获取方法 - EXPECT_FALSE(source->fetchAircraftData(aircraft)); - EXPECT_FALSE(source->fetchVehicleData(vehicles)); - EXPECT_FALSE(source->fetchTrafficLightSignals(signals)); - - // 验证数据集为空 - EXPECT_TRUE(aircraft.empty()); - EXPECT_TRUE(vehicles.empty()); - EXPECT_TRUE(signals.empty()); -} - -// 添加一个新的测试用例,专门测试重连机制 -TEST_F(HTTPDataSourceTest, ReconnectionTest) { - // 配置一个较短的刷新间隔 - DataSourceConfig config; - config.host = "localhost"; - config.port = 1; // 使用一个通常不会被使用的端口 - config.refresh_interval_ms = 100; // 100毫秒的刷新间隔 - auto reconnectSource = std::make_unique(config); - - // 第一次连接应该失败 - EXPECT_FALSE(reconnectSource->connect()); - EXPECT_FALSE(reconnectSource->isAvailable()); - - // 尝试获取数据,这会触发重连 - std::vector aircraft; - EXPECT_FALSE(reconnectSource->fetchAircraftData(aircraft)); - EXPECT_TRUE(aircraft.empty()); -} - -// 如果你的环境支持模拟网络响应,可以添加更多测试 -TEST_F(HTTPDataSourceTest, InvalidResponseTest) { - // 这个测试需要模拟无效的服务器响应 - // 你可能需要使用 mock 对象或者设置一个返回无效数据的测试服务器 - source->connect(); - std::vector aircraft; - // 假设服务器返回无效的 JSON 数据 - // EXPECT_FALSE(source->fetchAircraftData(aircraft)); -} - -// 测试不同的超时配置 -TEST_F(HTTPDataSourceTest, DifferentTimeoutConfigTest) { - // 测试读取超时小于连接超时 - { - DataSourceConfig config; - config.host = "localhost"; - config.port = 8081; - config.timeout_ms = 5000; // 连接超时 5 秒 - config.read_timeout_ms = 2000; // 读取超时 2 秒 - - auto source = std::make_unique(config); - EXPECT_FALSE(source->isAvailable()); // 只验证初始状态 - - std::vector aircraft; - EXPECT_FALSE(source->fetchAircraftData(aircraft)); - EXPECT_TRUE(aircraft.empty()); - } - - // 测试读取超时等于连接超时 - { - DataSourceConfig config; - config.host = "localhost"; - config.port = 8081; - config.timeout_ms = 5000; // 连接超时 5 秒 - config.read_timeout_ms = 5000; // 读取超时 5 秒 - - auto source = std::make_unique(config); - EXPECT_FALSE(source->isAvailable()); // 只验证初始状态 - - std::vector aircraft; - EXPECT_FALSE(source->fetchAircraftData(aircraft)); - EXPECT_TRUE(aircraft.empty()); - } -} - -// 修改读取超时测试 -TEST_F(HTTPDataSourceTest, ReadTimeoutTest) { - DataSourceConfig config; - config.host = "localhost"; - config.port = 8081; - config.timeout_ms = 5000; // 连接超时 5 秒 - config.read_timeout_ms = 2000; // 读取超时 2 秒 - - auto source = std::make_unique(config); - EXPECT_FALSE(source->isAvailable()); // 验证初始状态 - - std::vector aircraft; - EXPECT_FALSE(source->fetchAircraftData(aircraft)); - EXPECT_TRUE(aircraft.empty()); -} - -// 修改连接健康和超时测试 -TEST_F(HTTPDataSourceTest, ConnectionHealthAndTimeout) { - DataSourceConfig config; - config.host = "localhost"; - config.port = 8081; - config.timeout_ms = 5000; // 连接超时 5 秒 - config.read_timeout_ms = 2000; // 读取超时 2 秒 - - auto source = std::make_unique(config); - EXPECT_FALSE(source->isAvailable()); // 验证初始状态 - - std::vector aircraft; - EXPECT_FALSE(source->fetchAircraftData(aircraft)); - EXPECT_TRUE(aircraft.empty()); + VehicleCommand command; + command.vehicleId = "TEST_VEHICLE_001"; + command.type = CommandType::SIGNAL; + command.reason = CommandReason::RESUME_TRAFFIC; + command.signalState = SignalState::GREEN; + command.timestamp = 0; + EXPECT_FALSE(source.sendUnmannedVehicleCommand(command.vehicleId, command)); } \ No newline at end of file diff --git a/tests/SafetyZoneTest.cpp b/tests/SafetyZoneTest.cpp index 41d0d2c..9cfbcfb 100644 --- a/tests/SafetyZoneTest.cpp +++ b/tests/SafetyZoneTest.cpp @@ -76,6 +76,9 @@ TEST_F(SafetyZoneTest, AircraftEntering) { // 检查飞机是否在安全区内 EXPECT_TRUE(safetyZone->isObjectInZone(aircraft)); + + // 尝试激活安全区 + EXPECT_TRUE(safetyZone->tryActivate(aircraft)); EXPECT_EQ(safetyZone->getType(), SafetyZoneType::AIRCRAFT); EXPECT_EQ(safetyZone->getCurrentRadius(), 50.0); @@ -93,6 +96,9 @@ TEST_F(SafetyZoneTest, SpecialVehicleEntering) { // 检查特勤车是否在安全区内 EXPECT_TRUE(safetyZone->isObjectInZone(vehicle)); + + // 尝试激活安全区 + EXPECT_TRUE(safetyZone->tryActivate(vehicle)); EXPECT_EQ(safetyZone->getType(), SafetyZoneType::VEHICLE); EXPECT_EQ(safetyZone->getCurrentRadius(), 30.0); @@ -107,7 +113,8 @@ TEST_F(SafetyZoneTest, UnmannedVehicleEntering) { auto vehicle = createUnmannedVehicle("UV001", 10.0, 0.0); // 检查无人车是否在安全区内(应该返回false,因为无人车不能设置安全区类型) - EXPECT_FALSE(safetyZone->isObjectInZone(vehicle)); + EXPECT_TRUE(safetyZone->isObjectInZone(vehicle)); + EXPECT_FALSE(safetyZone->tryActivate(vehicle)); EXPECT_EQ(safetyZone->getType(), SafetyZoneType::NONE); EXPECT_EQ(safetyZone->getCurrentRadius(), 0.0); } @@ -120,13 +127,15 @@ TEST_F(SafetyZoneTest, SafetyZoneTypeLocking) { // 先让飞机进入安全区 auto aircraft = createAircraft("AC001", aircraftEffectiveDistance - 5.0, 0.0); EXPECT_TRUE(safetyZone->isObjectInZone(aircraft)); + EXPECT_TRUE(safetyZone->tryActivate(aircraft)); EXPECT_EQ(safetyZone->getType(), SafetyZoneType::AIRCRAFT); // 尝试让特勤车进入已经被飞机设置类型的安全区 auto vehicle = createSpecialVehicle("TQ001", vehicleEffectiveDistance - 5.0, 0.0); - EXPECT_FALSE(safetyZone->isObjectInZone(vehicle)); + EXPECT_TRUE(safetyZone->isObjectInZone(vehicle)); + EXPECT_FALSE(safetyZone->tryActivate(vehicle)); - // 确认安全区类型和尺寸没有改��� + // 确认安全区类型和尺寸没有改变 EXPECT_EQ(safetyZone->getType(), SafetyZoneType::AIRCRAFT); EXPECT_EQ(safetyZone->getCurrentRadius(), 50.0); } @@ -139,15 +148,19 @@ TEST_F(SafetyZoneTest, BoundaryConditions) { // 测试飞机在边界上 auto aircraft1 = createAircraft("AC001", aircraftEffectiveDistance, 0.0); EXPECT_TRUE(safetyZone->isObjectInZone(aircraft1)); + EXPECT_TRUE(safetyZone->tryActivate(aircraft1)); // 测试飞机在边界外 auto aircraft2 = createAircraft("AC002", aircraftEffectiveDistance + 0.1, 0.0); EXPECT_FALSE(safetyZone->isObjectInZone(aircraft2)); - // 测试特勤车在边界上 + // 重新创建安全区用于测试特勤车 safetyZone = std::make_unique(Vector2D{0, 0}, 50.0, 30.0); + + // 测试特勤车在边界上 auto vehicle1 = createSpecialVehicle("TQ001", vehicleEffectiveDistance, 0.0); EXPECT_TRUE(safetyZone->isObjectInZone(vehicle1)); + EXPECT_TRUE(safetyZone->tryActivate(vehicle1)); // 测试特勤车在边界外 auto vehicle2 = createSpecialVehicle("TQ002", vehicleEffectiveDistance + 0.1, 0.0); @@ -161,6 +174,7 @@ TEST_F(SafetyZoneTest, StateReset) { // 先让飞机进入安全区 auto aircraft = createAircraft("AC001", effectiveDistance - 5.0, 0.0); EXPECT_TRUE(safetyZone->isObjectInZone(aircraft)); + EXPECT_TRUE(safetyZone->tryActivate(aircraft)); // 设置状态为激活 safetyZone->setState(SafetyZoneState::ACTIVE); diff --git a/tools/map.html b/tools/map.html new file mode 100644 index 0000000..7c2dbd7 --- /dev/null +++ b/tools/map.html @@ -0,0 +1,303 @@ + + + + + 机场路口地图 + + + +
+

机场路口地图

+ +
+

图例

+
+
+ 道路 +
+
+
+ 路口 +
+
+
+ + + + \ No newline at end of file diff --git a/tools/map_websocket.html b/tools/map_websocket.html index 8ee927a..19de9ea 100644 --- a/tools/map_websocket.html +++ b/tools/map_websocket.html @@ -90,6 +90,9 @@ .traffic-light-green { background-color: green; } + .traffic-light-yellow { + background-color: yellow; + } .countdown-label { background: #000; border: 1px solid #666; @@ -114,6 +117,9 @@ .countdown-green { color: #33ff33; } + .countdown-yellow { + color: #ffff33; + } .distance-label { background: none; border: none; @@ -303,7 +309,7 @@ function updateTrafficLight(data) { const id = data.id; const position = [data.position.latitude, data.position.longitude]; - const state = data.status === 0 ? 'red' : 'green'; + const state = data.status === 0 ? 'red' : data.status === 1 ? 'green' : 'yellow'; // 检查是否是西路口(TL001)的红绿灯状态变化 if (id === 'TL001' && lastTrafficLightState !== state) { @@ -464,7 +470,7 @@ case 'traffic_light_status': type = 'info'; updateTrafficLight(data); - message = `红绿灯状态更新:\n信号灯: ${data.id}\n状态: ${data.status === 0 ? '红灯' : '绿灯'}`; + message = `红绿灯状态更新:\n信号灯: ${data.id}\n状态: ${data.status === 0 ? '红灯' : data.status === 1 ? '绿灯' : '黄灯'}`; break; case 'collision_warning': type = 'warning'; diff --git a/tools/mock_server.py b/tools/mock_server.py index def421a..c26cf1b 100644 --- a/tools/mock_server.py +++ b/tools/mock_server.py @@ -3,6 +3,21 @@ import time import math import random import logging +import os + +# 创建 logs 目录(如果不存在) +if not os.path.exists('logs'): + os.makedirs('logs') + +# 配置日志 +logging.basicConfig( + level=logging.DEBUG, + format='%(asctime)s - %(levelname)s - %(message)s', + handlers=[ + logging.FileHandler('logs/mock_server.log'), + logging.StreamHandler() + ] +) app = Flask(__name__) @@ -11,7 +26,8 @@ EARTH_RADIUS = 6378137.0 COMMAND_PRIORITIES = { "ALERT": 5, - "SIGNAL": 4, + "RED": 4, + "YELLOW": 3, "WARNING": 3, "GREEN": 2, "RESUME": 1 @@ -164,6 +180,7 @@ class VehicleState: priority_map = { "ALERT": 5, # 告警指令,最高优先级 "RED": 4, # 红灯指令,次高优先级 + "YELLOW": 3, # 黄灯指令,表示红绿灯故障 "WARNING": 3, # 预警指令,中等优先级 "GREEN": 2, # 绿灯状态,低优先级 "RESUME": 1 # 恢复指令,最低优先级 @@ -175,19 +192,23 @@ class VehicleState: if self.current_command == "ALERT": return command_type == "RESUME" - # RED 指令可以被 GREEN 或更高优先级指令覆盖 + # RED 指令可以被 GREEN 或相同及更高优先级指令覆盖 if self.current_command == "RED": - return command_type == "GREEN" or new_priority > current_priority + return command_type == "GREEN" or new_priority >= current_priority - # WARNING 指令可以被 RESUME 解除 + # YELLOW 指令(红绿灯故障)可以被任何新指令覆盖 + if self.current_command == "YELLOW": + return True + + # WARNING 指令可以被 RESUME 或相同及更高优先级指令覆盖 if self.current_command == "WARNING": - return command_type == "RESUME" or new_priority > current_priority + return command_type == "RESUME" or new_priority >= current_priority # GREEN 不阻止任何指令 if self.current_command == "GREEN": return True - # 其他情况按优先级判断 + # 其他情况下,相同或更高优先级可以覆盖 return new_priority >= current_priority def update_command(self, command_type, target_lat=None, target_lon=None): @@ -195,6 +216,7 @@ class VehicleState: priority_map = { "ALERT": 5, # 告警指令,最高优先级 "RED": 4, # 红灯指令,次高优先级 + "YELLOW": 3, # 黄灯指令,表示红绿灯故障 "WARNING": 3, # 预警指令,中等优先级 "GREEN": 2, # 绿灯状态,低优先级 "RESUME": 1 # 恢复指令,最低优先级 @@ -206,13 +228,19 @@ class VehicleState: self.target_lon = target_lon # 如果是红绿灯状态,更新状态和指令 - if command_type in ["RED", "GREEN"]: + if command_type in ["RED", "GREEN", "YELLOW"]: self.traffic_light_state = command_type if command_type == "RED": self.current_command = command_type self.command_priority = priority_map[command_type] self.is_running = False print(f"车辆 {self.vehicle_no} 收到红灯指令,停止运行") + elif command_type == "YELLOW": + # 黄灯表示红绿灯故障,清除当前红绿灯状态,允许车辆继续行驶 + self.current_command = command_type + self.command_priority = priority_map[command_type] + self.is_running = True + print(f"车辆 {self.vehicle_no} 收到黄灯指令(红绿灯故障),继续行驶") else: # GREEN # 清除 RED 指令 if self.current_command == "RED": @@ -297,9 +325,9 @@ def handle_vehicle_command(): print(f"收到车辆控制指令: vehicle_id={vehicle_id}, type={command_type}, reason={reason}, signal_state={signal_state}") print(f"完整请求数据: {data}") - # 将 SIGNAL 指令转换为 RED 或 GREEN + # 将 SIGNAL 指令转换为 RED、YELLOW 或 GREEN if command_type == "SIGNAL": - command_type = "RED" if signal_state == "RED" else "GREEN" + command_type = signal_state # 直接使用信号状态作为命令类型 print(f"转换 SIGNAL 指令为: {command_type}") # 检查车辆是否存在 @@ -804,9 +832,24 @@ def switch_traffic_light_state(): # 西路口红绿灯每15秒切换一次 elapsed_since_switch = current_time - last_light_switch_time if elapsed_since_switch >= TRAFFIC_LIGHT_SWITCH_INTERVAL: # 使用常量 - traffic_light_data[0]["state"] = 1 if traffic_light_data[0]["state"] == 0 else 0 + # 获取当前状态 + current_state = traffic_light_data[0]["state"] + + # 根据当前状态决定下一个状态 + if current_state == 0: # 当前是红灯 + # 切换到黄灯(表示红绿灯故障) + traffic_light_data[0]["state"] = 2 # 2 表示黄灯 + print(f"西路口红绿灯状态切换为: 黄灯(红绿灯故障)") + elif current_state == 2: # 当前是黄灯 + # 从黄灯切换到绿灯 + traffic_light_data[0]["state"] = 1 # 1 表示绿灯 + print(f"西路口红绿灯状态切换为: 绿灯") + else: # 当前是绿灯 + # 从绿灯切换到红灯 + traffic_light_data[0]["state"] = 0 # 0 表示红灯 + print(f"西路口红绿灯状态切换为: 红灯") + last_light_switch_time = current_time - print(f"西路口红绿灯状态切换为: {'绿灯' if traffic_light_data[0]['state'] == 1 else '红灯'}") # 更新东路口红绿灯(根据航空器位置) if aircraft_data: @@ -859,26 +902,24 @@ def get_vehicle_positions(): "data": None }), 500 -@app.route('/getTrafficLightSignals', methods=['GET', 'OPTIONS']) +@app.route('/openApi/getTrafficLightSignals', methods=['GET', 'OPTIONS']) def get_traffic_light_signals(): + """获取红绿灯信号状态""" if request.method == 'OPTIONS': return '', 204 - if not check_auth(): - return jsonify({ - "status": 401, - "msg": "认证失败", - "data": None - }), 401 - current_time = time.time() - # 更新时间戳 - for light in traffic_light_data: - light["timestamp"] = int(current_time * 1000) - - # 统一处理红绿灯状态切换 + # 更新红绿灯状态 switch_traffic_light_state() - return jsonify(traffic_light_data) + # 更新时间戳 + for signal in traffic_light_data: + signal["timestamp"] = int(time.time() * 1000) + + return jsonify({ + "status": 200, + "msg": "获取红绿灯信号成功", + "data": traffic_light_data + }) @app.after_request def add_cors_headers(response): @@ -932,5 +973,42 @@ def login(): "data": None }), 401 +@app.route('/openApi/getVehicleStatus', methods=['GET', 'OPTIONS']) +def get_vehicle_status(): + """获取无人车状态信息""" + if request.method == 'OPTIONS': + return '', 204 + + vehicle_id = request.args.get('vehicleId') + if not vehicle_id: + return jsonify({ + "status": 400, + "msg": "缺少 vehicleId 参数", + "data": None + }), 400 + + # 查找对应的车辆 + vehicle_state = vehicle_states.get(vehicle_id) + if not vehicle_state: + return jsonify({ + "status": 404, + "msg": f"未找到车辆 {vehicle_id}", + "data": None + }), 404 + + # 返回车辆状态 + return jsonify({ + "status": 200, + "msg": "获取车辆状态成功", + "data": { + "vehicleId": vehicle_id, + "status": "NORMAL" if vehicle_state.is_running else "STOPPED", + "command": vehicle_state.current_command, + "commandPriority": vehicle_state.command_priority, + "trafficLightState": vehicle_state.traffic_light_state, + "timestamp": int(time.time() * 1000) + } + }) + if __name__ == '__main__': app.run(host='localhost', port=8081, debug=True) \ No newline at end of file