From ccf5cba67239557151595389e1d7379d4d49d6ee Mon Sep 17 00:00:00 2001 From: TY <1431301249@qq.com> Date: Mon, 12 Jan 2026 10:00:53 +0800 Subject: [PATCH] =?UTF-8?q?=E4=B8=8A=E4=BC=A0=E6=96=87=E4=BB=B6=E8=87=B3?= =?UTF-8?q?=20include/dispatch?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- include/dispatch/advanced_dispatcher.h | 97 ++++++++ include/dispatch/agv_executor.h | 270 ++++++++++++++++++++++ include/dispatch/agv_manager_base.h | 171 ++++++++++++++ include/dispatch/agv_manager_standalone.h | 121 ++++++++++ include/dispatch/enhanced_agv_manager.h | 204 ++++++++++++++++ 5 files changed, 863 insertions(+) create mode 100644 include/dispatch/advanced_dispatcher.h create mode 100644 include/dispatch/agv_executor.h create mode 100644 include/dispatch/agv_manager_base.h create mode 100644 include/dispatch/agv_manager_standalone.h create mode 100644 include/dispatch/enhanced_agv_manager.h diff --git a/include/dispatch/advanced_dispatcher.h b/include/dispatch/advanced_dispatcher.h new file mode 100644 index 0000000..89a8d97 --- /dev/null +++ b/include/dispatch/advanced_dispatcher.h @@ -0,0 +1,97 @@ +#ifndef ADVANCED_DISPATCHER_H +#define ADVANCED_DISPATCHER_H + +#include "graph_map.h" +#include "agv_manager_base.h" +#include "resource_manager.h" +#include +#include +#include +#include + +/** + * @brief 高级调度器统计信息 + */ +struct DispatcherStatistics { + uint64_t total_tasks; + uint64_t completed_tasks; + uint64_t failed_tasks; + uint64_t active_agvs; + + DispatcherStatistics() + : total_tasks(0), completed_tasks(0), failed_tasks(0), active_agvs(0) {} +}; + +/** + * @brief 高级调度器 - 基于图的多AGV任务调度系统 + */ +class AdvancedDispatcher { +public: + enum class DispatcherState { + STOPPED, // 停止 + RUNNING, // 运行中 + PAUSED // 暂停 + }; + +private: + // 核心组件 + GraphMap* graph_map_; + ResourceManager* resource_manager_; + AGVManagerBase* agv_manager_; + + // 调度器状态 + std::atomic state_; + std::atomic should_stop_; + + // 调度线程 + std::thread dispatch_thread_; + + // 调度参数 + int dispatch_interval_ms_; // 调度间隔(毫秒) + + // 统计信息 + DispatcherStatistics statistics_; + + // 任务队列(简化实现) + std::vector> task_queue_; + mutable std::mutex task_mutex_; + + // 互斥锁 + mutable std::mutex dispatcher_mutex_; + +public: + AdvancedDispatcher(GraphMap* map, ResourceManager* resource_manager); + AdvancedDispatcher(GraphMap* map, ResourceManager* resource_manager, AGVManagerBase* agv_manager); + ~AdvancedDispatcher(); + + // ==================== 系统控制 ==================== + bool start(); + void stop(); + void pause(); + void resume(); + DispatcherState getState() const { return state_.load(); } + + // ==================== 任务管理 ==================== + bool addTask(int task_id, int start_point_id, int end_point_id, + const std::string& description, int priority = 1); + bool cancelTask(int task_id); + + // ==================== 任务执行反馈 ==================== + void onTaskStarted(int task_id, int agv_id); + void onTaskCompleted(int task_id, int agv_id, bool success); + + // ==================== 配置和监控 ==================== + void setDispatchInterval(int interval_ms) { dispatch_interval_ms_ = interval_ms; } + DispatcherStatistics getStatistics(); + + void printSystemStatus() const; + +private: + // ==================== 内部方法 ==================== + void dispatchLoop(); + void performDispatch(); + bool assignTaskToAGV(Task* task, AGV* agv); + void updateStatistics(); +}; + +#endif // ADVANCED_DISPATCHER_H \ No newline at end of file diff --git a/include/dispatch/agv_executor.h b/include/dispatch/agv_executor.h new file mode 100644 index 0000000..02aef5d --- /dev/null +++ b/include/dispatch/agv_executor.h @@ -0,0 +1,270 @@ +#ifndef AGV_EXECUTOR_H +#define AGV_EXECUTOR_H + +#include "resource_manager.h" +#include "enhanced_agv_manager.h" +#include +#include +#include +#include +#include +#include + +/** + * @brief AGV执行器 + * 负责AGV路径的分段执行和资源管理 + */ +class AGVExecutor { +public: + /** + * @brief 执行状态 + */ + enum class ExecutionState { + IDLE, // 空闲 + PLANNING, // 规划中 + REQUESTING, // 请求资源 + EXECUTING, // 执行中 + WAITING, // 等待资源 + COMPLETED, // 已完成 + ERROR, // 错误 + PAUSED // 暂停 + }; + +private: + AGV* agv_; // AGV指针 + ResourceManager* resource_manager_; // 资源管理器 + GraphMap* graph_map_; // 地图 + + // 执行状态 + std::atomic state_; + std::atomic should_stop_; + std::atomic is_paused_; + + // 路径信息 + std::vector planned_path_; // 完整规划路径 + size_t current_path_index_; // 当前路径索引 + Path* current_executing_path_; // 当前执行路径 + + // 执行线程 + std::thread execution_thread_; + mutable std::mutex execution_mutex_; + std::condition_variable execution_cv_; + + // 配置参数 + int request_timeout_ms_; // 资源请求超时时间(毫秒) + int execution_interval_ms_; // 执行间隔(毫秒) + double speed_factor_; // 速度因子(实际速度/最大速度) + + // 统计信息 + std::atomic total_paths_executed_; + std::atomic total_wait_time_; + std::atomic total_execution_time_; + + // 回调函数 + std::function path_started_callback_; + std::function path_completed_callback_; + std::function error_callback_; + +public: + AGVExecutor(AGV* agv, ResourceManager* resource_manager, GraphMap* graph_map); + + ~AGVExecutor(); + + /** + * @brief 设置执行参数 + */ + void setParameters(int request_timeout_ms = 5000, + int execution_interval_ms = 100, + double speed_factor = 1.0); + + /** + * @brief 开始执行路径 + * @param path 要执行的路径列表 + * @return 是否成功开始执行 + */ + bool startExecution(const std::vector& path); + + /** + * @brief 暂停执行 + */ + void pauseExecution(); + + /** + * @brief 恢复执行 + */ + void resumeExecution(); + + /** + * @brief 停止执行 + */ + void stopExecution(); + + /** + * @brief 强制停止(紧急情况) + */ + void forceStop(); + + /** + * @brief 获取执行状态 + */ + ExecutionState getState() const { return state_.load(); } + + /** + * @brief 获取当前执行的路径 + */ + Path* getCurrentPath() const; + + /** + * @brief 获取进度 + * @return 已完成的路径数 / 总路径数 + */ + std::pair getProgress() const; + + /** + * @brief 获取统计信息 + */ + void getStatistics(uint64_t& total_paths, uint64_t& wait_time, + uint64_t& execution_time) const; + + /** + * @brief 设置路径开始回调 + */ + void setPathStartedCallback(std::function callback) { + path_started_callback_ = callback; + } + + /** + * @brief 设置路径完成回调 + */ + void setPathCompletedCallback(std::function callback) { + path_completed_callback_ = callback; + } + + /** + * @brief 设置错误回调 + */ + void setErrorCallback(std::function callback) { + error_callback_ = callback; + } + + /** + * @brief 是否正在执行 + */ + bool isExecuting() const { + ExecutionState s = state_.load(); + return s == ExecutionState::PLANNING || s == ExecutionState::REQUESTING || + s == ExecutionState::EXECUTING || s == ExecutionState::WAITING; + } + + /** + * @brief 状态转换为字符串 + */ + static std::string stateToString(ExecutionState state); + +private: + /** + * @brief 执行线程主循环 + */ + void executionLoop(); + + /** + * @brief 执行单段路径 + * @param path 要执行的路径 + * @return 是否成功 + */ + bool executePathSegment(Path* path); + + /** + * @brief 请求路径资源 + * @param path 要请求的路径 + * @return 是否成功获取资源 + */ + bool requestPathResource(Path* path); + + /** + * @brief 释放路径资源 + * @param path 要释放的路径 + */ + void releasePathResource(Path* path); + + /** + * @brief 移动到下一个路径 + * @return 是否成功 + */ + bool moveToNextPath(); + + /** + * @brief 模拟路径执行 + * @param path 要执行的路径 + * @return 执行时间(毫秒) + */ + int simulatePathExecution(Path* path); + + /** + * @brief 处理错误 + * @param error_message 错误信息 + */ + void handleError(const std::string& error_message); + + /** + * @brief 更新AGV位置 + * @param path 执行完成的路径 + */ + void updateAGVPosition(Path* path); +}; + +/** + * @brief AGV执行器管理器 + * 管理所有AGV的执行器 + */ +class AGVExecutorManager { +private: + std::unordered_map> executors_; + ResourceManager* resource_manager_; + GraphMap* graph_map_; + +public: + AGVExecutorManager(ResourceManager* resource_manager, GraphMap* graph_map); + + /** + * @brief 添加AGV执行器 + */ + void addAGVExecutor(AGV* agv); + + /** + * @brief 移除AGV执行器 + */ + void removeAGVExecutor(int agv_id); + + /** + * @brief 获取AGV执行器 + */ + AGVExecutor* getExecutor(int agv_id); + + /** + * @brief 停止所有执行器 + */ + void stopAll(); + + /** + * @brief 暂停所有执行器 + */ + void pauseAll(); + + /** + * @brief 恢复所有执行器 + */ + void resumeAll(); + + /** + * @brief 获取执行统计 + */ + void getStatistics(std::map>& progress) const; + + /** + * @brief 打印所有执行器状态 + */ + void printStatus() const; +}; + +#endif // AGV_EXECUTOR_H \ No newline at end of file diff --git a/include/dispatch/agv_manager_base.h b/include/dispatch/agv_manager_base.h new file mode 100644 index 0000000..b9585df --- /dev/null +++ b/include/dispatch/agv_manager_base.h @@ -0,0 +1,171 @@ +#ifndef AGV_MANAGER_BASE_H +#define AGV_MANAGER_BASE_H + +#include "graph_map.h" +#include +#include +#include + +/** + * @brief AGV状态枚举 + */ +enum class AGVState { + IDLE, // 空闲 + ASSIGNED, // 已分配任务 + MOVING, // 移动中 + LOADING, // 装载中 + UNLOADING, // 卸载中 + CHARGING, // 充电中 + ERROR, // 错误状态 + MAINTENANCE // 维护中 +}; + +/** + * @brief 任务状态枚举 + */ +enum class TaskStatus { + PENDING, // 待处理 + ASSIGNED, // 已分配 + IN_PROGRESS, // 执行中 + COMPLETED, // 已完成 + FAILED // 失败 +}; + +// 前向声明以解决循环依赖 +struct Task; +struct AGV; + +/** + * @brief AGV小车结构 + */ +struct AGV { + int id; + std::string name; + AGVState state; + Point* current_position; + double x, y; // 坐标位置 + double battery_level; // 电量百分比 + double max_speed; // 最大速度 + Task* current_task; // 当前任务 + + AGV() + : id(0), name(""), state(AGVState::IDLE), current_position(nullptr), + x(0), y(0), battery_level(100.0), max_speed(2.0), current_task(nullptr) {} +}; + +/** + * @brief 任务结构 + */ +struct Task { + int id; + int priority; + Point* start_point; + Point* end_point; + std::string description; + TaskStatus status; + AGV* assigned_agv; + + Task(int task_id, int prio, Point* start, Point* end, const std::string& desc) + : id(task_id), priority(prio), start_point(start), end_point(end), + description(desc), status(TaskStatus::PENDING), assigned_agv(nullptr) {} +}; + +/** + * @brief AGV基础管理器 + * 提供AGV管理的基本功能,供EnhancedAGVManager继承 + */ +class AGVManagerBase { +protected: + GraphMap* map_; + std::unordered_map agvs_; + std::vector> task_queue_; + std::unordered_map> agv_paths_; + +public: + AGVManagerBase(GraphMap* map) : map_(map) {} + virtual ~AGVManagerBase() = default; + + /** + * @brief 添加AGV到管理器 + */ + virtual void addAGV(int id, double x, double y, const std::string& name = ""); + + /** + * @brief 移除AGV + */ + virtual void removeAGV(int id); + + /** + * @brief 获取AGV + */ + AGV* getAGV(int id); + + /** + * @brief 获取所有AGV + */ + std::vector getAllAGVs(); + + /** + * @brief 获取空闲AGV列表 + */ + std::vector getIdleAGVs(); + + /** + * @brief 获取AGV数量 + */ + size_t getAGVCount() const { return agvs_.size(); } + + /** + * @brief 添加任务到队列 + */ + virtual void addTask(int task_id, int start_point_id, int end_point_id, + const std::string& description, int priority = 1); + + /** + * @brief 获取待处理任务 + */ + std::vector getPendingTasks(); + + /** + * @brief 为AGV设置路径 + */ + void setAGVPath(int agv_id, const std::vector& path); + + /** + * @brief 获取AGV的当前路径 + */ + std::vector getAGVPath(int agv_id); + + /** + * @brief 清除AGV路径 + */ + void clearAGVPath(int agv_id); + + /** + * @brief 任务分配(基类实现简单的FIFO分配) + */ + virtual int assignTasks(); + + /** + * @brief 打印AGV状态 + */ + virtual void printAGVStatus(); + + /** + * @brief 打印任务队列状态 + */ + virtual void printTaskQueue(); + +protected: + /** + * @brief 寻找路径(使用GraphMap的A*算法) + */ + std::vector findPath(AGV* agv, Task* task); + + /** + * @brief 计算两点间距离 + */ + double calculateDistance(AGV* agv, Task* task); +}; + +#endif // AGV_MANAGER_BASE_H \ No newline at end of file diff --git a/include/dispatch/agv_manager_standalone.h b/include/dispatch/agv_manager_standalone.h new file mode 100644 index 0000000..236b889 --- /dev/null +++ b/include/dispatch/agv_manager_standalone.h @@ -0,0 +1,121 @@ +#ifndef AGV_MANAGER_STANDALONE_H +#define AGV_MANAGER_STANDALONE_H + +#include "graph_map.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/** + * @brief AGV状态枚举 + */ +enum class AGVState { + IDLE, // 空闲 + ASSIGNED, // 已分配任务 + PLANNING, // 路径规划中 + EXECUTING, // 执行任务中 + WAITING, // 等待资源 + ERROR // 错误状态 +}; + +/** + * @brief 任务结构 + */ +struct Task { + int id; + int priority; + int start_point_id; + int end_point_id; + std::string description; + + Task(int task_id, int prio, int start, int end, const std::string& desc) + : id(task_id), priority(prio), start_point_id(start), end_point_id(end), description(desc) {} +}; + +/** + * @brief AGV小车结构 + */ +struct AGV { + int id; + std::string name; + AGVState state; + Point* current_position; + double battery_level; // 电量百分比 + double max_velocity; // 最大速度 + Task* current_task; // 当前任务 + std::vector planned_path; // 规划的路径 + size_t path_index; // 当前路径索引 + + AGV(int agv_id, const std::string& agv_name, int start_point_id, Point* pos) + : id(agv_id), name(agv_name), state(AGVState::IDLE), current_position(pos), + battery_level(100.0), max_velocity(2.0), current_task(nullptr), path_index(0) {} +}; + +/** + * @brief AGV管理器 + */ +class AGVManager { +private: + GraphMap* graph_map_; + std::unordered_map> agvs_; + std::priority_queue, std::function> task_queue_; + mutable std::mutex agv_mutex_; + mutable std::mutex task_mutex_; + std::atomic next_task_id_{1}; + +public: + explicit AGVManager(GraphMap* map); + ~AGVManager() = default; + + // AGV管理 + AGV* addAGV(int id, const std::string& name, int start_point_id); + AGV* getAGV(int id); + std::vector getAllAGVs(); + std::vector getIdleAGVs(); + + // 任务管理 + int addTask(int priority, int start_point_id, int end_point_id, const std::string& description = ""); + bool assignTask(AGV* agv, Task* task); + int assignTasks(); + void completeTask(AGV* agv, bool success = true); + + // 路径规划 + bool planPath(AGV* agv, Task* task); + + // 状态查询 + size_t getAGVCount() const; + size_t getTaskQueueSize() const; + std::vector getPendingTasks(); + + // 事件回调 + void setTaskCompleteCallback(std::function callback) { + task_complete_callback_ = callback; + } + + // 统计信息 + struct Statistics { + int total_agvs; + int idle_agvs; + int busy_agvs; + int pending_tasks; + double average_battery_level; + }; + + Statistics getStatistics() const; + +private: + std::function task_complete_callback_; + + void initializeTaskQueue(); + bool isValidTask(const Task* task) const; + bool canAssignTask(const AGV* agv, const Task* task) const; + double calculateDistance(AGV* agv, const Task* task) const; +}; + +#endif // AGV_MANAGER_STANDALONE_H \ No newline at end of file diff --git a/include/dispatch/enhanced_agv_manager.h b/include/dispatch/enhanced_agv_manager.h new file mode 100644 index 0000000..a238838 --- /dev/null +++ b/include/dispatch/enhanced_agv_manager.h @@ -0,0 +1,204 @@ +#ifndef ENHANCED_AGV_MANAGER_H +#define ENHANCED_AGV_MANAGER_H + +#include "agv_manager_base.h" +#include "resource_manager.h" +#include +#include + +/** + * @brief AGV分配策略枚举 + */ +enum class AssignmentStrategy { + FIRST_FIT, // 第一个适配(当前策略) + NEAREST_FIT, // 最近适配 + BATTERY_AWARE, // 考虑电量 + LOAD_BALANCED, // 负载均衡 + PRIORITY_BASED, // 基于优先级 + COST_OPTIMAL // 成本最优 +}; + +/** + * @brief AGV评估结果 + */ +struct AGVEvaluation { + AGV* agv; + double score; // 评估分数 + double estimated_time; // 预计完成时间 + double distance_to_task; // 到任务起点的距离 + std::string reason; // 选择原因 + + AGVEvaluation(AGV* a, double s, double t, double d, const std::string& r) + : agv(a), score(s), estimated_time(t), distance_to_task(d), reason(r) {} +}; + +/** + * @brief 任务分配选项 + */ +struct AssignmentOption { + Task* task; + AGV* agv; + std::vector path; + double total_cost; // 总成本(时间、距离等) + double estimated_duration; // 预计执行时间 + double battery_consumption; // 预计电量消耗 + + AssignmentOption(Task* t, AGV* a, const std::vector& p, double c, double d, double b) + : task(t), agv(a), path(p), total_cost(c), estimated_duration(d), battery_consumption(b) {} +}; + +/** + * @brief 增强的AGV管理器 + * 支持多种任务分配策略 + */ +class EnhancedAGVManager : public AGVManagerBase { +private: + AssignmentStrategy strategy_; // 当前分配策略 + std::unordered_map> scoring_functions_; + ResourceManager* resource_manager_; // 资源管理器集成 + + // 分配权重 + struct AssignmentWeights { + double distance_weight = 0.4; // 距离权重 + double battery_weight = 0.3; // 电量权重 + double load_weight = 0.2; // 负载权重 + double speed_weight = 0.1; // 速度权重 + } weights_; + +public: + EnhancedAGVManager(GraphMap* map, ResourceManager* resource_mgr = nullptr, AssignmentStrategy strategy = AssignmentStrategy::NEAREST_FIT) + : AGVManagerBase(map), strategy_(strategy), resource_manager_(resource_mgr) { + initializeScoringFunctions(); + } + + /** + * @brief 设置资源管理器 + */ + void setResourceManager(ResourceManager* resource_mgr) { + resource_manager_ = resource_mgr; + } + + /** + * @brief 设置分配策略 + */ + void setStrategy(AssignmentStrategy strategy) { + strategy_ = strategy; + } + + /** + * @brief 设置分配权重 + */ + void setWeights(const AssignmentWeights& weights) { + weights_ = weights; + } + + /** + * @brief 智能任务分配 + * 使用当前策略找到最优的AGV-任务匹配 + */ + int assignTasksSmart(); + + /** + * @brief 为特定任务寻找最佳AGV + * @param task 要分配的任务 + * @param exclude_excluded 排除已分配任务的AGV + * @return 评估结果列表,按分数排序 + */ + std::vector findBestAGVForTask(Task* task, bool exclude_assigned = true); + + /** + * @brief 计算任务-AGV匹配的成本 + */ + double calculateAssignmentCost(AGV* agv, Task* task, std::vector& path); + + /** + * @brief 批量任务分配优化 + * 同时考虑多个任务,找到全局最优分配 + */ + std::vector optimizeBatchAssignment(std::vector& tasks, + std::vector& available_agvs); + + /** + * @brief 预测AGV在未来时间段的可用性 + */ + std::pair predictAvailability(AGV* agv, double future_time); + + /** + * @brief 获取AGV负载情况 + */ + double getAGVLoad(AGV* agv); + + /** + * @brief 打印分配策略分析 + */ + void printAssignmentAnalysis(); + + /** + * @brief 完成任务并释放资源 + */ + void completeTaskWithResources(AGV* agv, bool success = true); + +private: + void initializeScoringFunctions(); + + // 各种分配策略的评分函数 + double scoreFirstFit(AGV* agv, Task* task, double distance); + double scoreNearestFit(AGV* agv, Task* task, double distance); + double scoreBatteryAware(AGV* agv, Task* task, double distance); + double scoreLoadBalanced(AGV* agv, Task* task, double distance); + double scorePriorityBased(AGV* agv, Task* task, double distance); + double scoreCostOptimal(AGV* agv, Task* task, double distance); + + // 辅助函数 + double calculateDistance(AGV* agv, Task* task); + double calculateBatteryConsumption(AGV* agv, Task* task, double distance); + double calculateLoadFactor(AGV* agv); + std::vector findPathWithAvoidance(AGV* agv, Task* task); + std::string getReasonForSelection(AGV* agv, Task* task, double distance, double score); + std::string agvStateToString(AGVState state); + + // 新增辅助方法 + bool assignSingleTask(AGV* agv, Task* task); + std::string assignmentStrategyToString(AssignmentStrategy strategy); +}; + +/** + * @brief 任务分配分析器 + * 用于分析和优化分配策略 + */ +class AssignmentAnalyzer { +private: + struct Metrics { + double avg_completion_time; + double agv_utilization; + double battery_efficiency; + int task_count; + int reassignments; + }; + + std::unordered_map strategy_metrics_; + +public: + /** + * @brief 记录任务分配结果 + */ + void recordAssignment(AssignmentStrategy strategy, AGV* agv, Task* task, + double completion_time, double battery_used); + + /** + * @brief 获取最优策略 + */ + AssignmentStrategy getOptimalStrategy(); + + /** + * @brief 生成分配报告 + */ + void generateReport(); + + /** + * @brief 重置统计数据 + */ + void reset(); +}; + +#endif // ENHANCED_AGV_MANAGER_H \ No newline at end of file