Removed core engine infrastructure from warfactoryracine: - Core interfaces: IEngine, IModule, IModuleSystem, IIO, ITaskScheduler, ICoordinationModule - Configuration system: IDataTree, IDataNode, DataTreeFactory - UI system: IUI, IUI_Enums, ImGuiUI (header + implementation) - Resource management: Resource, ResourceRegistry, SerializationRegistry - Serialization: ASerializable, ISerializable - World generation: IWorldGenerationStep (replaced by IWorldGenerationPhase) These components now live in the GroveEngine repository and are included via CMake add_subdirectory(../GroveEngine) for reusability across projects. warfactoryracine remains focused on game-specific logic and content. 🤖 Generated with [Claude Code](https://claude.com/claude-code) Co-Authored-By: Claude <noreply@anthropic.com>
2234 lines
66 KiB
Markdown
2234 lines
66 KiB
Markdown
# Système de Pathfinding Hybride
|
||
|
||
## Vue d'Ensemble
|
||
|
||
Le système de pathfinding de Warfactory utilise une **architecture hybride à 3 algorithmes** pour optimiser performance et précision selon le contexte tactique. Ce n'est pas un simple A* : c'est un système adaptatif qui choisit automatiquement le bon algorithme selon la distance, le nombre d'unités, et les contraintes tactiques.
|
||
|
||
### Principes Fondamentaux
|
||
|
||
- **Hybride** : A*, HPA*, Flow Fields selon contexte
|
||
- **Poids Dynamiques** : Threat maps, cover, terrain, doctrine
|
||
- **Multi-Path** : Génération chemins alternatifs (flanking)
|
||
- **Tactique** : Cover-to-cover, évitement menaces, choix terrain
|
||
- **Performance** : Budget 4ms/frame (60fps), scaling linéaire
|
||
|
||
---
|
||
|
||
## Architecture Globale
|
||
|
||
### Les 3 Algorithmes
|
||
|
||
```cpp
|
||
enum PathfindingAlgorithm {
|
||
ASTAR, // Courte distance, précision
|
||
HIERARCHICAL, // Longue distance, rapide
|
||
FLOW_FIELD // Groupes massifs, 1 calcul pour N unités
|
||
};
|
||
|
||
PathfindingAlgorithm selectAlgorithm(Unit unit, Position goal) {
|
||
float distance = calculateDistance(unit.pos, goal);
|
||
int group_size = countUnitsWithSameGoal(unit, goal);
|
||
|
||
// Groupe massif → Flow Field
|
||
if (group_size >= 10) {
|
||
return FLOW_FIELD;
|
||
}
|
||
|
||
// Longue distance → Hierarchical
|
||
if (distance > 100.0f) {
|
||
return HIERARCHICAL;
|
||
}
|
||
|
||
// Court + précis → A*
|
||
return ASTAR;
|
||
}
|
||
```
|
||
|
||
### Règles de Décision
|
||
|
||
| Situation | Algorithme | Raison | Performance |
|
||
|-----------|------------|--------|-------------|
|
||
| 1 unité, < 100m | A* | Précision tactique | 1-2ms |
|
||
| 1 unité, > 100m | HPA* | Vitesse longue distance | 5-10ms |
|
||
| 10+ unités, même but | Flow Field | 1 calcul partagé | 15ms total |
|
||
| N unités, buts différents | A* × N ou HPA* × N | Chemins divergents | Variable |
|
||
|
||
---
|
||
|
||
## 1. A* - Pathfinding Précis
|
||
|
||
### Usage
|
||
|
||
**Quand** :
|
||
- Distance courte (< 100m)
|
||
- Unité solo ou petit groupe (< 10)
|
||
- Besoin précision tile-par-tile
|
||
- Mouvement tactique (cover-to-cover)
|
||
|
||
**Performance Target** :
|
||
- < 2ms pour 50m
|
||
- < 5ms pour 100m
|
||
- Budget : 25% d'un frame (4ms @ 60fps)
|
||
|
||
### Algorithme de Base
|
||
|
||
```cpp
|
||
class AStarPathfinder {
|
||
public:
|
||
Path findPath(Position start, Position goal, PathConstraints constraints) {
|
||
std::priority_queue<Node> open_set;
|
||
std::unordered_set<Position> closed_set;
|
||
|
||
Node start_node = {start, 0.0f, heuristic(start, goal)};
|
||
open_set.push(start_node);
|
||
|
||
while (!open_set.empty()) {
|
||
Node current = open_set.top();
|
||
open_set.pop();
|
||
|
||
if (current.pos == goal) {
|
||
return reconstructPath(current);
|
||
}
|
||
|
||
closed_set.insert(current.pos);
|
||
|
||
// Explorer voisins
|
||
for (auto& neighbor : getNeighbors(current.pos)) {
|
||
if (closed_set.contains(neighbor)) continue;
|
||
|
||
// ✅ COÛT AVEC POIDS DYNAMIQUES
|
||
float g_cost = current.g_cost + calculateCost(current, neighbor, constraints);
|
||
float h_cost = heuristic(neighbor, goal);
|
||
float f_cost = g_cost + h_cost;
|
||
|
||
open_set.push({neighbor, g_cost, f_cost});
|
||
}
|
||
}
|
||
|
||
return Path(); // Pas de chemin trouvé
|
||
}
|
||
|
||
private:
|
||
float heuristic(Position a, Position b) {
|
||
// Manhattan distance (grille 4-directionnelle)
|
||
return abs(a.x - b.x) + abs(a.y - b.y);
|
||
|
||
// Ou Euclidean (grille 8-directionnelle)
|
||
// return sqrt(pow(a.x - b.x, 2) + pow(a.y - b.y, 2));
|
||
}
|
||
};
|
||
```
|
||
|
||
### Poids Dynamiques (Weighted A*)
|
||
|
||
**Principe** : Coût ≠ distance pure, intègre facteurs tactiques
|
||
|
||
```cpp
|
||
float calculateCost(Node current, Node neighbor, PathConstraints constraints) {
|
||
float base_cost = distance(current.pos, neighbor.pos); // 1.0 ou 1.41 (diagonal)
|
||
|
||
// Poids tactiques
|
||
float threat_penalty = getThreat(neighbor.pos) * constraints.threat_weight;
|
||
float cover_bonus = hasCover(neighbor.pos) ? -constraints.cover_weight : 0.0f;
|
||
float elevation_penalty = abs(neighbor.elevation - current.elevation) * constraints.elevation_weight;
|
||
float terrain_penalty = getTerrainCost(neighbor.terrain, constraints.unit_type) * constraints.terrain_weight;
|
||
float exposure_penalty = isExposed(neighbor.pos) ? constraints.exposure_weight : 0.0f;
|
||
|
||
float total_cost = base_cost + threat_penalty + cover_bonus + elevation_penalty + terrain_penalty + exposure_penalty;
|
||
|
||
// Contraintes absolues
|
||
if (constraints.avoid_water && neighbor.terrain == WATER) {
|
||
return INFINITY; // Interdit
|
||
}
|
||
|
||
if (neighbor.slope > constraints.max_slope) {
|
||
return INFINITY; // Trop raide
|
||
}
|
||
|
||
return max(0.1f, total_cost); // Minimum 0.1 pour éviter coût nul
|
||
}
|
||
```
|
||
|
||
### PathConstraints Structure
|
||
|
||
```cpp
|
||
struct PathConstraints {
|
||
// Poids dynamiques (0.0 = ignore, higher = plus important)
|
||
float threat_weight = 1.0f; // Éviter zones menace
|
||
float cover_weight = 0.5f; // Préférer cover
|
||
float elevation_weight = 0.3f; // Pénalité montées/descentes
|
||
float terrain_weight = 1.0f; // Pénalité terrains difficiles
|
||
float exposure_weight = 0.8f; // Pénalité terrain ouvert
|
||
|
||
// Contraintes absolues
|
||
bool avoid_water = false;
|
||
bool avoid_roads = false;
|
||
bool prefer_roads = false;
|
||
float max_slope = 30.0f; // Degrés
|
||
|
||
// Contexte unité
|
||
UnitType unit_type = INFANTRY;
|
||
float unit_speed = 1.0f;
|
||
|
||
// Doctrine (preset poids)
|
||
Doctrine doctrine = BALANCED;
|
||
};
|
||
|
||
enum Doctrine {
|
||
AGGRESSIVE, // threat_weight=0.2, prefer_roads=true
|
||
BALANCED, // threat_weight=1.0, cover_weight=0.5
|
||
CAUTIOUS, // threat_weight=5.0, cover_weight=3.0
|
||
STEALTH // threat_weight=10.0, exposure_weight=5.0, avoid_roads=true
|
||
};
|
||
```
|
||
|
||
### Multi-Path A* (Chemins Divergents)
|
||
|
||
**Usage** : Flanking, chemins alternatifs tactiques
|
||
|
||
```cpp
|
||
std::vector<Path> findAllPaths(Position start, Position goal, int max_paths, PathConstraints constraints) {
|
||
std::vector<Path> paths;
|
||
std::unordered_set<Position> penalized_nodes;
|
||
|
||
for (int i = 0; i < max_paths; i++) {
|
||
// A* avec pénalités sur nœuds déjà utilisés
|
||
Path path = aStarWithPenalties(start, goal, constraints, penalized_nodes);
|
||
|
||
if (path.empty()) break; // Plus de chemins valides
|
||
|
||
paths.push_back(path);
|
||
|
||
// Pénalise 40% milieu du chemin (garde start/goal communs)
|
||
int start_idx = path.waypoints.size() * 0.3;
|
||
int end_idx = path.waypoints.size() * 0.7;
|
||
|
||
for (int j = start_idx; j < end_idx; j++) {
|
||
penalized_nodes.insert(path.waypoints[j]);
|
||
}
|
||
}
|
||
|
||
return paths;
|
||
}
|
||
|
||
Path aStarWithPenalties(Position start, Position goal, PathConstraints constraints,
|
||
const std::unordered_set<Position>& penalized) {
|
||
// A* standard mais avec coût additionnel pour nœuds pénalisés
|
||
// cost += penalized.contains(node) ? PENALTY_COST : 0.0f;
|
||
// PENALTY_COST = 50.0 (force divergence sans interdire)
|
||
}
|
||
```
|
||
|
||
### Exemples d'Utilisation
|
||
|
||
#### Exemple 1 : Mouvement Simple
|
||
|
||
```cpp
|
||
PathConstraints basic;
|
||
basic.threat_weight = 1.0f;
|
||
basic.unit_type = INFANTRY;
|
||
|
||
Path path = pathfinder->findPath(soldier.pos, objective, basic);
|
||
// Chemin équilibré, évite menaces modérément
|
||
```
|
||
|
||
#### Exemple 2 : Tank Blessé (Priorité Survie)
|
||
|
||
```cpp
|
||
PathConstraints wounded;
|
||
wounded.threat_weight = 10.0f; // ÉVITER COMBAT
|
||
wounded.cover_weight = 5.0f; // MAXIMUM COVER
|
||
wounded.terrain_weight = 0.5f; // Distance secondaire
|
||
wounded.unit_type = TANK_MEDIUM;
|
||
|
||
Path path = pathfinder->findPath(damaged_tank.pos, repair_base, wounded);
|
||
// Peut doubler distance mais SÉCURISÉ
|
||
```
|
||
|
||
#### Exemple 3 : Flanking 3 Directions
|
||
|
||
```cpp
|
||
PathConstraints flanking;
|
||
flanking.threat_weight = 3.0f;
|
||
flanking.cover_weight = 2.0f;
|
||
flanking.exposure_weight = 5.0f;
|
||
|
||
auto paths = pathfinder->findAllPaths(tank.pos, enemy.pos, 3, flanking);
|
||
|
||
// paths[0] : Frontal (court, threat=HIGH)
|
||
// paths[1] : Flanking gauche (détour, threat=MEDIUM, cover=HIGH)
|
||
// paths[2] : Flanking droite (long, threat=LOW)
|
||
|
||
// TacticalModule score et choisit
|
||
int best_idx = tacticalModule->selectBestPath(paths, enemy);
|
||
tank.setPath(paths[best_idx]);
|
||
```
|
||
|
||
---
|
||
|
||
## 2. HPA* - Hierarchical Pathfinding
|
||
|
||
### Usage
|
||
|
||
**Quand** :
|
||
- Distance longue (> 100m)
|
||
- Traversée multi-chunks
|
||
- Navigation stratégique
|
||
- Pas besoin précision tile-par-tile
|
||
|
||
**Performance Target** :
|
||
- < 5ms pour 500m
|
||
- < 10ms pour 5000m
|
||
- Scaling logarithmique avec distance
|
||
|
||
### Concept Hiérarchique
|
||
|
||
```
|
||
NIVEAU 1 : Abstraction Globale (Clusters 256×256)
|
||
Map 2048×2048 divisée en 8×8 clusters
|
||
|
||
[Cluster A] --edge--> [Cluster B] --edge--> [Cluster C]
|
||
↓ ↓ ↓
|
||
Start (traversée) Goal
|
||
|
||
NIVEAU 2 : Chemins Intra-Cluster (Pré-calculés)
|
||
Dans Cluster A : Entry → Exit (A* cached)
|
||
Dans Cluster B : Entry → Exit (A* cached)
|
||
Dans Cluster C : Entry → Goal (A* cached)
|
||
|
||
NIVEAU 3 : Smoothing Final
|
||
Combine chemins clusters + smooth transitions
|
||
```
|
||
|
||
### Architecture
|
||
|
||
```cpp
|
||
class HierarchicalPathfinder {
|
||
public:
|
||
Path findPath(Position start, Position goal, PathConstraints constraints) {
|
||
// 1. Identifier clusters start/goal
|
||
ClusterId start_cluster = getCluster(start);
|
||
ClusterId goal_cluster = getCluster(goal);
|
||
|
||
// 2. A* sur graphe abstrait clusters
|
||
std::vector<ClusterId> cluster_path = findClusterPath(start_cluster, goal_cluster);
|
||
|
||
// 3. Pour chaque cluster, récupérer chemin intra-cluster (cached)
|
||
Path full_path;
|
||
for (int i = 0; i < cluster_path.size(); i++) {
|
||
ClusterId cluster = cluster_path[i];
|
||
|
||
Position entry = (i == 0) ? start : getClusterEntry(cluster, cluster_path[i-1]);
|
||
Position exit = (i == cluster_path.size()-1) ? goal : getClusterExit(cluster, cluster_path[i+1]);
|
||
|
||
Path segment = getIntraClusterPath(cluster, entry, exit, constraints);
|
||
full_path.append(segment);
|
||
}
|
||
|
||
// 4. Smooth path (éliminer waypoints redondants)
|
||
return smoothPath(full_path);
|
||
}
|
||
|
||
private:
|
||
struct Cluster {
|
||
int id;
|
||
Bounds bounds; // Rectangle 256×256
|
||
std::vector<Edge> edges; // Connexions autres clusters
|
||
PathCache intra_paths; // Chemins pré-calculés
|
||
};
|
||
|
||
struct Edge {
|
||
ClusterId from_cluster;
|
||
ClusterId to_cluster;
|
||
Position entry_point;
|
||
Position exit_point;
|
||
float cost; // Distance entre entry/exit
|
||
};
|
||
|
||
// Cache chemins intra-cluster
|
||
std::map<ClusterId, PathCache> cluster_caches;
|
||
};
|
||
```
|
||
|
||
### Cluster Graph Construction
|
||
|
||
```cpp
|
||
void buildClusterGraph() {
|
||
// 1. Diviser map en clusters 256×256
|
||
int clusters_x = map_width / CLUSTER_SIZE;
|
||
int clusters_y = map_height / CLUSTER_SIZE;
|
||
|
||
for (int x = 0; x < clusters_x; x++) {
|
||
for (int y = 0; y < clusters_y; y++) {
|
||
Cluster cluster = createCluster(x, y);
|
||
clusters.push_back(cluster);
|
||
}
|
||
}
|
||
|
||
// 2. Identifier edges entre clusters adjacents
|
||
for (auto& cluster : clusters) {
|
||
// Check voisins (4-directional)
|
||
for (auto& neighbor : getAdjacentClusters(cluster)) {
|
||
// Trouver points passage entre clusters
|
||
auto edges = findClusterEdges(cluster, neighbor);
|
||
cluster.edges.insert(cluster.edges.end(), edges.begin(), edges.end());
|
||
}
|
||
}
|
||
|
||
// 3. Pré-calculer chemins intra-cluster (edges → edges)
|
||
for (auto& cluster : clusters) {
|
||
precomputeIntraClusterPaths(cluster);
|
||
}
|
||
}
|
||
|
||
std::vector<Edge> findClusterEdges(Cluster a, Cluster b) {
|
||
std::vector<Edge> edges;
|
||
|
||
// Frontière entre clusters
|
||
Bounds border = getBorderBounds(a, b);
|
||
|
||
// Scan border, trouver passages navigables
|
||
for (int i = 0; i < border.length; i++) {
|
||
Position pos = border.start + i;
|
||
|
||
if (isWalkable(pos)) {
|
||
// Début passage
|
||
Position entry = pos;
|
||
|
||
// Trouver fin passage
|
||
while (isWalkable(pos) && i < border.length) {
|
||
pos = border.start + (++i);
|
||
}
|
||
Position exit = pos - 1;
|
||
|
||
// Créer edge (peut être multi-tiles large)
|
||
Edge edge = {a.id, b.id, entry, exit, distance(entry, exit)};
|
||
edges.push_back(edge);
|
||
}
|
||
}
|
||
|
||
return edges;
|
||
}
|
||
```
|
||
|
||
### Path Caching
|
||
|
||
```cpp
|
||
class PathCache {
|
||
public:
|
||
Path getCachedPath(Position start, Position goal) {
|
||
CacheKey key = {start, goal};
|
||
|
||
if (cache.contains(key)) {
|
||
return cache[key];
|
||
}
|
||
|
||
// Pas en cache, calculer avec A*
|
||
Path path = astar->findPath(start, goal);
|
||
cache[key] = path;
|
||
|
||
return path;
|
||
}
|
||
|
||
void invalidate(Position pos) {
|
||
// Obstacle ajouté/retiré, invalider chemins affectés
|
||
for (auto it = cache.begin(); it != cache.end();) {
|
||
if (pathContains(it->second, pos)) {
|
||
it = cache.erase(it);
|
||
} else {
|
||
++it;
|
||
}
|
||
}
|
||
}
|
||
|
||
private:
|
||
struct CacheKey {
|
||
Position start;
|
||
Position goal;
|
||
|
||
bool operator==(const CacheKey& other) const {
|
||
return start == other.start && goal == other.goal;
|
||
}
|
||
};
|
||
|
||
std::unordered_map<CacheKey, Path> cache;
|
||
};
|
||
```
|
||
|
||
### Optimisations
|
||
|
||
**1. Multi-Level Hierarchies**
|
||
|
||
Pour maps très grandes (> 4096×4096), utiliser 3+ niveaux :
|
||
|
||
```
|
||
Niveau 1 : Méga-clusters 1024×1024 (abstraction continents)
|
||
Niveau 2 : Clusters 256×256 (abstraction régions)
|
||
Niveau 3 : A* local 64×64 (précision tactique)
|
||
```
|
||
|
||
**2. Dynamic Edge Costs**
|
||
|
||
Mettre à jour coûts edges selon congestion, menaces :
|
||
|
||
```cpp
|
||
void updateEdgeCosts() {
|
||
for (auto& edge : edges) {
|
||
// Base cost (distance)
|
||
float cost = distance(edge.entry, edge.exit);
|
||
|
||
// Congestion (nb unités traversant)
|
||
int congestion = countUnitsInEdge(edge);
|
||
cost += congestion * CONGESTION_PENALTY;
|
||
|
||
// Menace (ennemis proximité)
|
||
float threat = getThreatLevel(edge.entry, edge.exit);
|
||
cost += threat * THREAT_PENALTY;
|
||
|
||
edge.cost = cost;
|
||
}
|
||
}
|
||
```
|
||
|
||
---
|
||
|
||
## 3. Flow Fields - Mouvement de Groupe
|
||
|
||
### Usage
|
||
|
||
**Quand** :
|
||
- Groupe massif (≥ 10 unités)
|
||
- Même destination
|
||
- Contraintes tactiques identiques
|
||
- RTS-style group movement
|
||
|
||
**Performance Target** :
|
||
- < 15ms pour 50 unités
|
||
- < 20ms pour 100 unités
|
||
- < 30ms pour 500 unités
|
||
- Scaling linéaire avec nombre unités
|
||
|
||
### Concept Flow Field
|
||
|
||
Au lieu de calculer N chemins individuels, calcule **1 champ vectoriel** que toutes les unités suivent.
|
||
|
||
```
|
||
Destination = G
|
||
|
||
Chaque tile contient vecteur direction optimale :
|
||
|
||
↗ ↗ ↗ → → →
|
||
↗ ↗ ↗ → → G
|
||
↑ ↗ → → ↑ ↑
|
||
↑ ↑ → # # #
|
||
↑ ↑ ↑ # # #
|
||
S ↑ ↑ # # #
|
||
|
||
Unité en S : Lit vecteur ↑, se déplace nord
|
||
Unité en (2,2) : Lit vecteur ↗, se déplace nord-est
|
||
|
||
100 unités : 1 seul field calculé!
|
||
```
|
||
|
||
### Algorithme Dijkstra Inverse
|
||
|
||
```cpp
|
||
class FlowFieldGenerator {
|
||
public:
|
||
FlowField generate(Position goal, PathConstraints constraints) {
|
||
// 1. Créer cost field (coût depuis goal)
|
||
CostField cost_field = generateCostField(goal, constraints);
|
||
|
||
// 2. Générer integration field (Dijkstra depuis goal)
|
||
IntegrationField integration_field = integrateField(cost_field, goal);
|
||
|
||
// 3. Générer flow field (gradients direction)
|
||
FlowField flow_field = generateFlowVectors(integration_field);
|
||
|
||
return flow_field;
|
||
}
|
||
|
||
private:
|
||
CostField generateCostField(Position goal, PathConstraints constraints) {
|
||
CostField field(map_width, map_height);
|
||
|
||
// Chaque tile a coût basé sur terrain, menaces, etc.
|
||
for (int x = 0; x < map_width; x++) {
|
||
for (int y = 0; y < map_height; y++) {
|
||
Position pos = {x, y};
|
||
|
||
if (!isWalkable(pos)) {
|
||
field.set(pos, INFINITY);
|
||
} else {
|
||
float cost = calculateCost(pos, constraints);
|
||
field.set(pos, cost);
|
||
}
|
||
}
|
||
}
|
||
|
||
return field;
|
||
}
|
||
|
||
IntegrationField integrateField(CostField& cost_field, Position goal) {
|
||
IntegrationField integration(map_width, map_height, INFINITY);
|
||
|
||
// Dijkstra INVERSE (depuis goal vers toutes positions)
|
||
std::priority_queue<Node> open;
|
||
integration.set(goal, 0.0f);
|
||
open.push({goal, 0.0f});
|
||
|
||
while (!open.empty()) {
|
||
Node current = open.top();
|
||
open.pop();
|
||
|
||
for (auto& neighbor : getNeighbors(current.pos)) {
|
||
float cost = cost_field.get(neighbor);
|
||
if (cost == INFINITY) continue; // Non-walkable
|
||
|
||
float new_cost = integration.get(current.pos) + cost;
|
||
|
||
if (new_cost < integration.get(neighbor)) {
|
||
integration.set(neighbor, new_cost);
|
||
open.push({neighbor, new_cost});
|
||
}
|
||
}
|
||
}
|
||
|
||
return integration;
|
||
}
|
||
|
||
FlowField generateFlowVectors(IntegrationField& integration) {
|
||
FlowField flow(map_width, map_height);
|
||
|
||
// Pour chaque tile, calculer gradient (direction vers goal)
|
||
for (int x = 0; x < map_width; x++) {
|
||
for (int y = 0; y < map_height; y++) {
|
||
Position pos = {x, y};
|
||
|
||
// Trouver voisin avec coût minimum
|
||
Position best_neighbor = pos;
|
||
float min_cost = integration.get(pos);
|
||
|
||
for (auto& neighbor : getNeighbors(pos)) {
|
||
float cost = integration.get(neighbor);
|
||
if (cost < min_cost) {
|
||
min_cost = cost;
|
||
best_neighbor = neighbor;
|
||
}
|
||
}
|
||
|
||
// Vecteur direction
|
||
Vector2 direction = normalize(best_neighbor - pos);
|
||
flow.set(pos, direction);
|
||
}
|
||
}
|
||
|
||
return flow;
|
||
}
|
||
};
|
||
```
|
||
|
||
### Utilisation Flow Field
|
||
|
||
```cpp
|
||
void moveUnitAlongFlowField(Unit& unit, FlowField& field) {
|
||
// Lire direction depuis field
|
||
Vector2 direction = field.get(unit.pos);
|
||
|
||
// Appliquer mouvement
|
||
Vector2 desired_velocity = direction * unit.max_speed;
|
||
|
||
// Steering behaviors (éviter collisions)
|
||
Vector2 separation = calculateSeparation(unit);
|
||
Vector2 cohesion = calculateCohesion(unit);
|
||
|
||
unit.velocity = desired_velocity + separation * 0.5f + cohesion * 0.2f;
|
||
unit.pos += unit.velocity * delta_time;
|
||
}
|
||
|
||
Vector2 calculateSeparation(Unit& unit) {
|
||
// Éviter unités trop proches
|
||
Vector2 separation = {0, 0};
|
||
int count = 0;
|
||
|
||
for (auto& other : getNearbyUnits(unit, SEPARATION_RADIUS)) {
|
||
if (other.id == unit.id) continue;
|
||
|
||
Vector2 diff = unit.pos - other.pos;
|
||
float distance = length(diff);
|
||
|
||
if (distance > 0) {
|
||
separation += normalize(diff) / distance; // Repousse inversement proportionnel distance
|
||
count++;
|
||
}
|
||
}
|
||
|
||
if (count > 0) {
|
||
separation /= count;
|
||
}
|
||
|
||
return separation;
|
||
}
|
||
```
|
||
|
||
### Optimisations Flow Field
|
||
|
||
**1. Spatial Partitioning**
|
||
|
||
Ne générer field que dans zone active (autour groupe) :
|
||
|
||
```cpp
|
||
FlowField generateLocalField(Position goal, BoundingBox active_area) {
|
||
// Field seulement dans active_area (ex: 512×512 autour groupe)
|
||
// Réduit calcul de 2048×2048 → 512×512 (16× plus rapide)
|
||
}
|
||
```
|
||
|
||
**2. Multi-Resolution Fields**
|
||
|
||
```cpp
|
||
// Distant du goal : résolution basse (16×16 tiles par cell)
|
||
// Proche du goal : résolution haute (1×1 tiles par cell)
|
||
|
||
FlowField coarse_field = generate(goal, 16); // Loin
|
||
FlowField fine_field = generate(goal, 1); // Proche
|
||
|
||
Unit utilise field selon distance au goal
|
||
```
|
||
|
||
**3. Field Caching**
|
||
|
||
```cpp
|
||
std::unordered_map<Position, FlowField> field_cache;
|
||
|
||
FlowField getOrGenerateField(Position goal, PathConstraints constraints) {
|
||
CacheKey key = {goal, constraints.hash()};
|
||
|
||
if (field_cache.contains(key)) {
|
||
return field_cache[key];
|
||
}
|
||
|
||
FlowField field = generator.generate(goal, constraints);
|
||
field_cache[key] = field;
|
||
|
||
return field;
|
||
}
|
||
```
|
||
|
||
---
|
||
|
||
## Intégration Recastnavigation
|
||
|
||
### Recastnavigation = NavMesh Professionnel
|
||
|
||
Le projet a **déjà intégré** Recastnavigation (AAA-grade library).
|
||
|
||
**Composants** :
|
||
- **Recast** : Génération NavMesh depuis geometry
|
||
- **Detour** : Queries pathfinding sur NavMesh
|
||
- **DetourCrowd** : Crowd simulation, collision avoidance
|
||
- **DetourTileCache** : Streaming NavMesh par tiles
|
||
|
||
### NavMesh vs Grid
|
||
|
||
**Grid A*** :
|
||
```
|
||
. . . # # # . .
|
||
. . . # # # . .
|
||
. . . . . . . .
|
||
|
||
Chaque tile = walkable/blocked
|
||
Pathfinding sur grille discrète
|
||
```
|
||
|
||
**NavMesh (Recast)** :
|
||
```
|
||
Polygon 1
|
||
/----------\
|
||
/ \
|
||
| Obstacle | ← Zones navigables = polygones
|
||
| |
|
||
\ /
|
||
\----------/
|
||
Polygon 2
|
||
|
||
Pathfinding sur polygones continus
|
||
```
|
||
|
||
**Avantages NavMesh** :
|
||
- ✅ Moins de nœuds (polygones vs tiles)
|
||
- ✅ Mouvement plus naturel (any-angle)
|
||
- ✅ Optimisé AAA (Recast utilisé par des dizaines jeux)
|
||
|
||
### Architecture Hybride : NavMesh + Grid
|
||
|
||
**Proposition Warfactory** :
|
||
|
||
```cpp
|
||
// NavMesh pour A* et HPA*
|
||
Path findPath_NavMesh(Position start, Position goal) {
|
||
dtNavMeshQuery* query = navmesh->getQuery();
|
||
|
||
dtPolyRef start_poly = query->findNearestPoly(start);
|
||
dtPolyRef goal_poly = query->findNearestPoly(goal);
|
||
|
||
std::vector<dtPolyRef> poly_path;
|
||
query->findPath(start_poly, goal_poly, poly_path);
|
||
|
||
// Convertir poly path → waypoints
|
||
return convertToWaypoints(poly_path);
|
||
}
|
||
|
||
// Grid pour Flow Fields (plus simple génération field)
|
||
FlowField generateField_Grid(Position goal) {
|
||
// Dijkstra sur grille 64×64
|
||
// Plus efficace pour fields que NavMesh
|
||
}
|
||
```
|
||
|
||
**Justification** :
|
||
- NavMesh excelle pour chemins individuels (A*, HPA*)
|
||
- Grid plus simple pour flow fields (calcul uniforme)
|
||
|
||
### Intégration Chunks 64×64
|
||
|
||
```cpp
|
||
class NavMeshManager {
|
||
public:
|
||
// Génère NavMesh tile par chunk 64×64
|
||
void buildChunkNavMesh(Chunk& chunk) {
|
||
rcConfig config;
|
||
config.cs = 1.0f; // Cell size = 1m (tile size)
|
||
config.ch = 0.5f; // Cell height = 0.5m
|
||
config.walkableSlopeAngle = 45.0f;
|
||
config.walkableHeight = 2; // 2m min clearance
|
||
config.walkableClimb = 1; // 1m max step
|
||
config.walkableRadius = 1; // 1m agent radius
|
||
|
||
// Extraire geometry depuis chunk
|
||
rcPolyMesh* poly_mesh = generatePolyMesh(chunk, config);
|
||
|
||
// Créer NavMesh tile
|
||
dtNavMeshCreateParams params;
|
||
// ... setup params ...
|
||
|
||
unsigned char* nav_data = nullptr;
|
||
int nav_data_size = 0;
|
||
dtCreateNavMeshData(¶ms, &nav_data, &nav_data_size);
|
||
|
||
// Ajouter tile au NavMesh global
|
||
int tile_x = chunk.x / CHUNK_SIZE;
|
||
int tile_y = chunk.y / CHUNK_SIZE;
|
||
navmesh->addTile(nav_data, nav_data_size, 0, tile_x, tile_y);
|
||
}
|
||
|
||
// Rebuild tile si chunk modifié
|
||
void onChunkModified(Chunk& chunk) {
|
||
removeTile(chunk);
|
||
buildChunkNavMesh(chunk);
|
||
|
||
// Invalider chemins affectés
|
||
invalidatePathsInChunk(chunk);
|
||
}
|
||
|
||
private:
|
||
dtNavMesh* navmesh;
|
||
std::unordered_map<ChunkId, dtTileRef> chunk_tiles;
|
||
};
|
||
```
|
||
|
||
### Streaming NavMesh
|
||
|
||
```cpp
|
||
void updateNavMeshStreaming(Position player_pos) {
|
||
const int LOAD_RADIUS = 5; // Charger 5 chunks autour joueur
|
||
|
||
ChunkCoords player_chunk = getChunkCoords(player_pos);
|
||
|
||
// Charger chunks proches
|
||
for (int dx = -LOAD_RADIUS; dx <= LOAD_RADIUS; dx++) {
|
||
for (int dy = -LOAD_RADIUS; dy <= LOAD_RADIUS; dy++) {
|
||
ChunkCoords chunk = {player_chunk.x + dx, player_chunk.y + dy};
|
||
|
||
if (!isNavMeshTileLoaded(chunk)) {
|
||
loadNavMeshTile(chunk);
|
||
}
|
||
}
|
||
}
|
||
|
||
// Unload chunks lointains
|
||
for (auto& [chunk_id, tile_ref] : loaded_tiles) {
|
||
int distance = manhattanDistance(chunk_id, player_chunk);
|
||
|
||
if (distance > LOAD_RADIUS + 2) {
|
||
unloadNavMeshTile(chunk_id);
|
||
}
|
||
}
|
||
}
|
||
```
|
||
|
||
---
|
||
|
||
## Threat Maps & Tactical Pathfinding
|
||
|
||
### Threat Map Generation
|
||
|
||
```cpp
|
||
class ThreatMap {
|
||
public:
|
||
void update(std::vector<Enemy>& enemies) {
|
||
// Reset threat grid
|
||
threat_grid.fill(0.0f);
|
||
|
||
// Pour chaque ennemi, propager menace
|
||
for (auto& enemy : enemies) {
|
||
propagateThreat(enemy);
|
||
}
|
||
|
||
// Smooth field (blur Gaussien)
|
||
smoothThreats(SMOOTH_RADIUS);
|
||
}
|
||
|
||
float getThreat(Position pos) const {
|
||
return threat_grid.get(pos);
|
||
}
|
||
|
||
private:
|
||
void propagateThreat(Enemy& enemy) {
|
||
float range = enemy.weapon_range;
|
||
float firepower = enemy.firepower;
|
||
Position pos = enemy.position;
|
||
|
||
// Cercle de menace autour ennemi
|
||
int radius = (int)range;
|
||
|
||
for (int dx = -radius; dx <= radius; dx++) {
|
||
for (int dy = -radius; dy <= radius; dy++) {
|
||
float dist = sqrt(dx*dx + dy*dy);
|
||
|
||
if (dist > range) continue;
|
||
|
||
// Threat decay linéaire avec distance
|
||
float threat_value = firepower * (1.0f - dist / range);
|
||
|
||
// Line of sight check (optionnel, coûteux)
|
||
if (USE_LOS && !hasLineOfSight(pos, pos + Vector2{dx, dy})) {
|
||
threat_value *= 0.2f; // Menace réduite sans LOS
|
||
}
|
||
|
||
int x = pos.x + dx;
|
||
int y = pos.y + dy;
|
||
|
||
if (inBounds(x, y)) {
|
||
threat_grid.add({x, y}, threat_value);
|
||
}
|
||
}
|
||
}
|
||
}
|
||
|
||
void smoothThreats(int radius) {
|
||
// Blur Gaussien pour smooth transitions
|
||
Grid<float> temp = threat_grid;
|
||
|
||
for (int x = 0; x < width; x++) {
|
||
for (int y = 0; y < height; y++) {
|
||
float sum = 0.0f;
|
||
float weight_sum = 0.0f;
|
||
|
||
for (int dx = -radius; dx <= radius; dx++) {
|
||
for (int dy = -radius; dy <= radius; dy++) {
|
||
int nx = x + dx;
|
||
int ny = y + dy;
|
||
|
||
if (!inBounds(nx, ny)) continue;
|
||
|
||
float dist = sqrt(dx*dx + dy*dy);
|
||
float weight = exp(-dist*dist / (2.0f * radius*radius));
|
||
|
||
sum += temp.get({nx, ny}) * weight;
|
||
weight_sum += weight;
|
||
}
|
||
}
|
||
|
||
threat_grid.set({x, y}, sum / weight_sum);
|
||
}
|
||
}
|
||
}
|
||
|
||
Grid<float> threat_grid;
|
||
};
|
||
```
|
||
|
||
### Cover Map
|
||
|
||
```cpp
|
||
class CoverMap {
|
||
public:
|
||
void buildFromTerrain(TerrainMap& terrain) {
|
||
for (int x = 0; x < width; x++) {
|
||
for (int y = 0; y < height; y++) {
|
||
Position pos = {x, y};
|
||
|
||
CoverInfo info = analyzeCover(pos, terrain);
|
||
cover_grid.set(pos, info);
|
||
}
|
||
}
|
||
}
|
||
|
||
CoverInfo getCover(Position pos) const {
|
||
return cover_grid.get(pos);
|
||
}
|
||
|
||
private:
|
||
struct CoverInfo {
|
||
bool has_cover;
|
||
Vector2 cover_direction; // Direction protection
|
||
float cover_height; // 0.0 = pas cover, 1.0 = full cover
|
||
CoverType type; // WALL, ROCK, BUILDING, VEGETATION
|
||
};
|
||
|
||
CoverInfo analyzeCover(Position pos, TerrainMap& terrain) {
|
||
CoverInfo info;
|
||
info.has_cover = false;
|
||
|
||
// Check tiles adjacents pour obstacles
|
||
for (auto& dir : CARDINAL_DIRECTIONS) {
|
||
Position neighbor = pos + dir;
|
||
|
||
if (terrain.isObstacle(neighbor)) {
|
||
info.has_cover = true;
|
||
info.cover_direction = dir;
|
||
info.cover_height = terrain.getHeight(neighbor) / MAX_HEIGHT;
|
||
info.type = terrain.getCoverType(neighbor);
|
||
break;
|
||
}
|
||
}
|
||
|
||
return info;
|
||
}
|
||
|
||
Grid<CoverInfo> cover_grid;
|
||
};
|
||
```
|
||
|
||
### Cover-to-Cover Pathfinding
|
||
|
||
```cpp
|
||
Path findCoverToCoverPath(Position start, Position goal, ThreatMap& threats, CoverMap& covers) {
|
||
PathConstraints constraints;
|
||
constraints.threat_weight = 5.0f;
|
||
constraints.cover_weight = 3.0f;
|
||
|
||
// A* avec scoring spécial pour cover
|
||
Path path = astar->findPath(start, goal, constraints);
|
||
|
||
// Post-process : identifier points cover sur chemin
|
||
std::vector<Waypoint> cover_waypoints;
|
||
|
||
for (auto& wp : path.waypoints) {
|
||
CoverInfo cover = covers.getCover(wp.pos);
|
||
|
||
wp.has_cover = cover.has_cover;
|
||
wp.cover_quality = cover.cover_height;
|
||
|
||
if (cover.has_cover) {
|
||
wp.pause_duration = 2.0f; // Pause 2s dans cover
|
||
cover_waypoints.push_back(wp);
|
||
}
|
||
}
|
||
|
||
// Ajouter metadata pour MovementModule
|
||
path.cover_points = cover_waypoints;
|
||
path.movement_style = COVER_TO_COVER;
|
||
|
||
return path;
|
||
}
|
||
```
|
||
|
||
---
|
||
|
||
## Terrain Costs
|
||
|
||
### Terrain Types
|
||
|
||
```cpp
|
||
enum TerrainType {
|
||
ROAD, // Asphalte, béton
|
||
GRASS, // Prairie, herbe
|
||
FOREST, // Forêt dense
|
||
SWAMP, // Marécage
|
||
MOUNTAIN, // Montagne rocheuse
|
||
URBAN, // Ville, bâtiments
|
||
SAND, // Désert
|
||
SNOW, // Neige profonde
|
||
WATER, // Eau (généralement impassable)
|
||
RUBBLE // Décombres
|
||
};
|
||
```
|
||
|
||
### Cost Matrix (Terrain × UnitType)
|
||
|
||
```cpp
|
||
class TerrainCostTable {
|
||
public:
|
||
float getCost(TerrainType terrain, UnitType unit) const {
|
||
return cost_table[terrain][unit];
|
||
}
|
||
|
||
private:
|
||
// [Terrain][UnitType] = multiplicateur coût
|
||
static constexpr float cost_table[10][5] = {
|
||
// Infantry Tank_Light Tank_Heavy Wheeled Tracked
|
||
/* ROAD */ {0.5, 0.3, 0.3, 0.2, 0.4},
|
||
/* GRASS */ {1.0, 1.0, 1.2, 1.2, 0.9},
|
||
/* FOREST */ {1.5, 3.0, 5.0, 8.0, 2.5},
|
||
/* SWAMP */ {3.0, 8.0, 12.0, 15.0, 6.0},
|
||
/* MOUNTAIN */ {2.0, 5.0, 8.0, 99.0, 4.0},
|
||
/* URBAN */ {1.2, 2.0, 2.5, 1.5, 2.0},
|
||
/* SAND */ {1.8, 1.5, 2.0, 3.0, 1.2},
|
||
/* SNOW */ {2.5, 2.0, 3.0, 4.0, 1.8},
|
||
/* WATER */ {99.0, 99.0, 99.0, 99.0, 99.0},
|
||
/* RUBBLE */ {2.0, 3.0, 4.0, 5.0, 2.5}
|
||
};
|
||
};
|
||
```
|
||
|
||
### Dynamic Terrain Modification
|
||
|
||
```cpp
|
||
void onBuildingDestroyed(Building& building) {
|
||
// Bâtiment détruit → terrain devient RUBBLE
|
||
for (auto& tile : building.occupiedTiles()) {
|
||
terrain_map.setType(tile, RUBBLE);
|
||
}
|
||
|
||
// Rebuild NavMesh du chunk
|
||
Chunk& chunk = getChunk(building.pos);
|
||
navmesh_manager->onChunkModified(chunk);
|
||
|
||
// Invalider chemins passant par zone
|
||
pathfinder->invalidatePathsInArea(building.bounds);
|
||
}
|
||
|
||
void onCraterCreated(Position pos, float radius) {
|
||
// Explosion crée cratère → terrain difficile
|
||
for (int dx = -radius; dx <= radius; dx++) {
|
||
for (int dy = -radius; dy <= radius; dy++) {
|
||
float dist = sqrt(dx*dx + dy*dy);
|
||
if (dist <= radius) {
|
||
Position tile = pos + Vector2{dx, dy};
|
||
terrain_map.setType(tile, RUBBLE);
|
||
}
|
||
}
|
||
}
|
||
|
||
// Rebuild NavMesh
|
||
navmesh_manager->onChunkModified(getChunk(pos));
|
||
}
|
||
```
|
||
|
||
---
|
||
|
||
## Architecture Intégration ITaskScheduler
|
||
|
||
### Vue d'Ensemble
|
||
|
||
PathfinderModule utilise **ITaskScheduler** pour déléguer pathfinding lourd au thread pool global géré par IModuleSystem, tout en conservant des opérations sync pour flow fields et queries tactiques.
|
||
|
||
```
|
||
┌─────────────────────────────────────────┐
|
||
│ IModuleSystem (ThreadPool) │
|
||
│ ┌───────────────────────────────────┐ │
|
||
│ │ ITaskScheduler (Async) │ │
|
||
│ │ - A* pathfinding │ │
|
||
│ │ - HPA* pathfinding │ │
|
||
│ │ - Multi-path generation │ │
|
||
│ └───────────────────────────────────┘ │
|
||
└─────────────────────────────────────────┘
|
||
↓ scheduleTask()
|
||
↓ getCompletedTask()
|
||
┌─────────────────────────────────────────┐
|
||
│ PathfinderModule │
|
||
│ ┌──────────────┐ ┌─────────────────┐ │
|
||
│ │ IPathfinder │ │ FlowFieldCache │ │
|
||
│ │ (internal) │ │ (sync) │ │
|
||
│ └──────────────┘ └─────────────────┘ │
|
||
│ ┌──────────────┐ ┌─────────────────┐ │
|
||
│ │ ThreatMap │ │ NavMeshManager │ │
|
||
│ │ (sync) │ │ (sync) │ │
|
||
│ └──────────────┘ └─────────────────┘ │
|
||
└─────────────────────────────────────────┘
|
||
↓ publish()
|
||
↓ pull()
|
||
┌─────────────────────────────────────────┐
|
||
│ IIO (Pub/Sub) │
|
||
│ - pathfinder/requests │
|
||
│ - pathfinder/results │
|
||
│ - pathfinder/flow_fields │
|
||
└─────────────────────────────────────────┘
|
||
```
|
||
|
||
### Délégation Async vs Sync
|
||
|
||
| Opération | Threading | Justification |
|
||
|-----------|-----------|---------------|
|
||
| A* pathfinding | **ITaskScheduler (async)** | Peut prendre 5-10ms, bloque pas game loop |
|
||
| HPA* pathfinding | **ITaskScheduler (async)** | Longue distance, calcul lourd |
|
||
| Multi-path generation | **ITaskScheduler (async)** | 3× calculs A*, déléguer |
|
||
| Flow Fields | **Sync (cache)** | 15ms acceptable, 1 calcul pour N unités |
|
||
| Threat Map update | **Sync (periodic)** | Mise à jour 1×/seconde suffit |
|
||
| Cover queries | **Sync** | Lookup instantané (pre-computed) |
|
||
| NavMesh queries | **Sync** | Recastnavigation thread-safe, rapide |
|
||
|
||
---
|
||
|
||
## IPathfinder Interface (Internal)
|
||
|
||
Interface abstraite permettant swap Classic ↔ ML pathfinding.
|
||
|
||
```cpp
|
||
/**
|
||
* @brief Abstract pathfinding interface for algorithm implementations
|
||
*
|
||
* Allows swapping between Classic (A*/HPA*) and ML-based pathfinding
|
||
* without changing PathfinderModule code.
|
||
*/
|
||
class IPathfinder {
|
||
public:
|
||
virtual ~IPathfinder() = default;
|
||
|
||
/**
|
||
* @brief Find single optimal path
|
||
* @param start Starting position (float world space)
|
||
* @param goal Goal position (float world space)
|
||
* @param constraints Tactical constraints (threat, cover, terrain)
|
||
* @return Computed path with waypoints
|
||
*/
|
||
virtual Path findPath(Position start, Position goal,
|
||
PathConstraints constraints) = 0;
|
||
|
||
/**
|
||
* @brief Find N alternative paths for flanking
|
||
* @param start Starting position
|
||
* @param goal Goal position
|
||
* @param max_paths Number of alternative paths (default 3)
|
||
* @param constraints Tactical constraints
|
||
* @return Vector of divergent paths
|
||
*/
|
||
virtual std::vector<Path> findAllPaths(Position start, Position goal,
|
||
int max_paths,
|
||
PathConstraints constraints) = 0;
|
||
|
||
/**
|
||
* @brief Validate if path is still walkable
|
||
* @param path Path to validate
|
||
* @return true if path valid, false if obstacles appeared
|
||
*/
|
||
virtual bool validatePath(const Path& path) = 0;
|
||
};
|
||
|
||
// Classic implementation (A*, HPA*, multi-path)
|
||
class ClassicPathfinder : public IPathfinder {
|
||
Path findPath(Position start, Position goal, PathConstraints constraints) override;
|
||
std::vector<Path> findAllPaths(Position start, Position goal, int max_paths, PathConstraints constraints) override;
|
||
bool validatePath(const Path& path) override;
|
||
};
|
||
|
||
// ML implementation (future)
|
||
class MLPathfinder : public IPathfinder {
|
||
// Neural network trained on Classic pathfinder outputs
|
||
Path findPath(Position start, Position goal, PathConstraints constraints) override;
|
||
std::vector<Path> findAllPaths(Position start, Position goal, int max_paths, PathConstraints constraints) override;
|
||
bool validatePath(const Path& path) override;
|
||
};
|
||
```
|
||
|
||
---
|
||
|
||
## PathfinderModule Implementation
|
||
|
||
### Class Definition
|
||
|
||
```cpp
|
||
class PathfinderModule : public IModule {
|
||
private:
|
||
// ===== FRAMEWORK INTERFACES =====
|
||
ITaskScheduler* scheduler; // Thread pool delegation (provided by IModuleSystem)
|
||
IIO* io; // Pub/sub communication
|
||
|
||
// ===== INTERNAL COMPONENTS =====
|
||
|
||
// Pathfinding logic (swappable Classic ↔ ML)
|
||
std::unique_ptr<IPathfinder> pathfinder;
|
||
|
||
// Flow fields (sync, cached)
|
||
FlowFieldCache flow_cache;
|
||
|
||
// Tactical data (sync, periodic updates)
|
||
ThreatMap threat_map;
|
||
CoverMap cover_map;
|
||
|
||
// NavMesh (sync queries, managed by Recastnavigation)
|
||
NavMeshManager navmesh_mgr;
|
||
dtNavMesh* global_navmesh;
|
||
|
||
// Configuration
|
||
const IDataNode* config;
|
||
|
||
public:
|
||
// ========== IMODULE INTERFACE ==========
|
||
|
||
void setConfiguration(const IDataNode& config, IIO* io, ITaskScheduler* scheduler) override {
|
||
this->config = &config;
|
||
this->io = io;
|
||
this->scheduler = scheduler;
|
||
|
||
// Select pathfinder implementation from config
|
||
std::string impl = config.getString("pathfinder_impl", "classic");
|
||
|
||
if (impl == "classic") {
|
||
pathfinder = std::make_unique<ClassicPathfinder>();
|
||
}
|
||
else if (impl == "ml") {
|
||
pathfinder = std::make_unique<MLPathfinder>();
|
||
}
|
||
|
||
// Initialize NavMesh manager
|
||
navmesh_mgr.initialize(config.getChildNode("navmesh"));
|
||
|
||
// Build initial NavMesh for loaded chunks
|
||
buildInitialNavMesh();
|
||
}
|
||
|
||
json process(const json& input) override {
|
||
// 1. Process incoming requests via IIO
|
||
processIORequests();
|
||
|
||
// 2. Pull completed pathfinding tasks from ITaskScheduler
|
||
processCompletedTasks();
|
||
|
||
// 3. Periodic threat map update (1×/second)
|
||
if (shouldUpdateThreatMap()) {
|
||
updateThreatMapSync();
|
||
}
|
||
|
||
return {};
|
||
}
|
||
|
||
const IDataNode& getConfiguration() override {
|
||
return *config;
|
||
}
|
||
|
||
json getHealthStatus() override {
|
||
return {
|
||
{"module", "pathfinder"},
|
||
{"pathfinder_impl", pathfinder ? "active" : "null"},
|
||
{"pending_tasks", scheduler->hasCompletedTasks()},
|
||
{"flow_fields_cached", flow_cache.size()},
|
||
{"navmesh_tiles", navmesh_mgr.getTileCount()}
|
||
};
|
||
}
|
||
|
||
private:
|
||
// ========== REQUEST PROCESSING ==========
|
||
|
||
void processIORequests() {
|
||
// Pull requests from IIO
|
||
auto requests = io->pull("pathfinder/requests");
|
||
|
||
for (auto& req : requests) {
|
||
std::string type = req["type"];
|
||
|
||
if (type == "single_path") {
|
||
handleSinglePathRequest(req);
|
||
}
|
||
else if (type == "multi_path") {
|
||
handleMultiPathRequest(req);
|
||
}
|
||
else if (type == "flow_field") {
|
||
handleFlowFieldRequest(req);
|
||
}
|
||
else if (type == "tactical_query") {
|
||
handleTacticalQuery(req);
|
||
}
|
||
}
|
||
}
|
||
|
||
void handleSinglePathRequest(const json& req) {
|
||
// Delegate to ITaskScheduler (async multithread)
|
||
scheduler->scheduleTask("pathfinding", {
|
||
{"request_id", req["request_id"]},
|
||
{"unit_id", req["unit_id"]},
|
||
{"start", req["start"]},
|
||
{"goal", req["goal"]},
|
||
{"constraints", req["constraints"]},
|
||
{"path_type", "single"}
|
||
});
|
||
}
|
||
|
||
void handleMultiPathRequest(const json& req) {
|
||
// Delegate multi-path to ITaskScheduler
|
||
scheduler->scheduleTask("pathfinding", {
|
||
{"request_id", req["request_id"]},
|
||
{"unit_id", req["unit_id"]},
|
||
{"start", req["start"]},
|
||
{"goal", req["goal"]},
|
||
{"constraints", req["constraints"]},
|
||
{"path_type", "multi"},
|
||
{"max_paths", req.value("max_paths", 3)}
|
||
});
|
||
}
|
||
|
||
void handleFlowFieldRequest(const json& req) {
|
||
// Flow fields generated SYNC (15ms acceptable, 1 calc for N units)
|
||
Position goal = parsePosition(req["goal"]);
|
||
PathConstraints constraints = parseConstraints(req["constraints"]);
|
||
|
||
// Get or generate (cached)
|
||
FlowField field = flow_cache.getOrGenerate(goal, constraints);
|
||
FlowFieldId id = flow_cache.add(field);
|
||
|
||
// Publish immediately
|
||
io->publish("pathfinder/flow_fields", {
|
||
{"request_id", req["request_id"]},
|
||
{"field_id", id},
|
||
{"goal", req["goal"]}
|
||
});
|
||
}
|
||
|
||
void handleTacticalQuery(const json& req) {
|
||
// Tactical queries are sync (fast lookups)
|
||
std::string query_type = req["query_type"];
|
||
|
||
if (query_type == "nearest_cover") {
|
||
Position from = parsePosition(req["from"]);
|
||
Vector2 threat_dir = parseVector2(req["threat_direction"]);
|
||
float max_dist = req.value("max_distance", 50.0f);
|
||
|
||
Position cover_pos = findNearestCoverSync(from, threat_dir, max_dist);
|
||
|
||
io->publish("pathfinder/tactical_results", {
|
||
{"request_id", req["request_id"]},
|
||
{"query_type", "nearest_cover"},
|
||
{"result", {cover_pos.x, cover_pos.y}}
|
||
});
|
||
}
|
||
else if (query_type == "flanking_positions") {
|
||
Position target = parsePosition(req["target"]);
|
||
int count = req.value("count", 3);
|
||
float distance = req.value("distance", 30.0f);
|
||
|
||
auto positions = findFlankingPositionsSync(target, count, distance);
|
||
|
||
io->publish("pathfinder/tactical_results", {
|
||
{"request_id", req["request_id"]},
|
||
{"query_type", "flanking_positions"},
|
||
{"result", serializePositions(positions)}
|
||
});
|
||
}
|
||
}
|
||
|
||
// ========== TASK COMPLETION ==========
|
||
|
||
void processCompletedTasks() {
|
||
// Pull all completed pathfinding tasks from scheduler
|
||
while (scheduler->hasCompletedTasks() > 0) {
|
||
json result = scheduler->getCompletedTask();
|
||
|
||
// Add tactical metadata
|
||
enrichPathResult(result);
|
||
|
||
// Publish result via IIO
|
||
io->publish("pathfinder/results", result);
|
||
}
|
||
}
|
||
|
||
void enrichPathResult(json& result) {
|
||
// Add threat/cover metrics to path
|
||
if (result.contains("path")) {
|
||
auto waypoints = result["path"];
|
||
|
||
float total_threat = 0.0f;
|
||
int cover_count = 0;
|
||
|
||
for (auto& wp : waypoints) {
|
||
Position pos = {wp["x"], wp["y"]};
|
||
|
||
total_threat += threat_map.getThreat(pos);
|
||
if (cover_map.getCover(pos).has_cover) {
|
||
cover_count++;
|
||
}
|
||
}
|
||
|
||
result["threat_level"] = total_threat / waypoints.size();
|
||
result["cover_percentage"] = (float)cover_count / waypoints.size();
|
||
}
|
||
}
|
||
|
||
// ========== SYNC OPERATIONS ==========
|
||
|
||
bool shouldUpdateThreatMap() {
|
||
static int last_update_frame = 0;
|
||
int current_frame = getCurrentFrame();
|
||
|
||
// Update 1×/second (60 frames @ 60fps)
|
||
if (current_frame - last_update_frame >= 60) {
|
||
last_update_frame = current_frame;
|
||
return true;
|
||
}
|
||
|
||
return false;
|
||
}
|
||
|
||
void updateThreatMapSync() {
|
||
// Get enemies from game state (via IIO or direct query)
|
||
auto enemies = getEnemiesFromGameState();
|
||
|
||
// Update threat map (sync, ~2-5ms)
|
||
threat_map.update(enemies);
|
||
}
|
||
|
||
Position findNearestCoverSync(Position from, Vector2 threat_dir, float max_dist) {
|
||
// Sync lookup in pre-computed cover map
|
||
return cover_map.findNearest(from, threat_dir, max_dist);
|
||
}
|
||
|
||
std::vector<Position> findFlankingPositionsSync(Position target, int count, float distance) {
|
||
// Generate positions around target
|
||
std::vector<Position> positions;
|
||
|
||
float angle_step = 2.0f * M_PI / count;
|
||
|
||
for (int i = 0; i < count; i++) {
|
||
float angle = i * angle_step;
|
||
Position pos = {
|
||
target.x + cos(angle) * distance,
|
||
target.y + sin(angle) * distance
|
||
};
|
||
|
||
// Validate walkable
|
||
if (navmesh_mgr.isWalkable(pos)) {
|
||
positions.push_back(pos);
|
||
}
|
||
}
|
||
|
||
return positions;
|
||
}
|
||
};
|
||
```
|
||
|
||
---
|
||
|
||
## ITaskScheduler Backend (Execution)
|
||
|
||
Le backend est géré par **IModuleSystem** (pas par PathfinderModule).
|
||
|
||
```cpp
|
||
/**
|
||
* @brief Task execution in worker threads (managed by IModuleSystem)
|
||
*
|
||
* PathfinderModule delegates tasks via ITaskScheduler.
|
||
* MultithreadedModuleSystem executes tasks in thread pool.
|
||
*/
|
||
class MultithreadedModuleSystem : public IModuleSystem {
|
||
private:
|
||
ThreadPool thread_pool;
|
||
|
||
// Task scheduler per module
|
||
std::map<std::string, std::unique_ptr<TaskSchedulerImpl>> schedulers;
|
||
|
||
class TaskSchedulerImpl : public ITaskScheduler {
|
||
private:
|
||
ThreadPool* pool;
|
||
std::queue<json> completed_tasks;
|
||
std::mutex completed_mutex;
|
||
|
||
public:
|
||
void scheduleTask(const std::string& taskType, const json& taskData) override {
|
||
// Submit to thread pool
|
||
pool->enqueue([this, taskType, taskData]() {
|
||
json result;
|
||
|
||
if (taskType == "pathfinding") {
|
||
result = executePathfindingTask(taskData);
|
||
}
|
||
// ... other task types
|
||
|
||
// Store result
|
||
std::lock_guard<std::mutex> lock(completed_mutex);
|
||
completed_tasks.push(result);
|
||
});
|
||
}
|
||
|
||
int hasCompletedTasks() const override {
|
||
std::lock_guard<std::mutex> lock(completed_mutex);
|
||
return completed_tasks.size();
|
||
}
|
||
|
||
json getCompletedTask() override {
|
||
std::lock_guard<std::mutex> lock(completed_mutex);
|
||
|
||
if (completed_tasks.empty()) {
|
||
return {};
|
||
}
|
||
|
||
json result = completed_tasks.front();
|
||
completed_tasks.pop();
|
||
return result;
|
||
}
|
||
|
||
private:
|
||
json executePathfindingTask(const json& taskData) {
|
||
// Thread-local pathfinder (no shared state)
|
||
static thread_local ClassicPathfinder pathfinder;
|
||
|
||
Position start = parsePosition(taskData["start"]);
|
||
Position goal = parsePosition(taskData["goal"]);
|
||
PathConstraints constraints = parseConstraints(taskData["constraints"]);
|
||
|
||
if (taskData["path_type"] == "single") {
|
||
Path path = pathfinder.findPath(start, goal, constraints);
|
||
|
||
return {
|
||
{"task_type", "pathfinding"},
|
||
{"request_id", taskData["request_id"]},
|
||
{"unit_id", taskData["unit_id"]},
|
||
{"path", serializePath(path)}
|
||
};
|
||
}
|
||
else if (taskData["path_type"] == "multi") {
|
||
int max_paths = taskData["max_paths"];
|
||
auto paths = pathfinder.findAllPaths(start, goal, max_paths, constraints);
|
||
|
||
return {
|
||
{"task_type", "pathfinding"},
|
||
{"request_id", taskData["request_id"]},
|
||
{"unit_id", taskData["unit_id"]},
|
||
{"paths", serializePaths(paths)}
|
||
};
|
||
}
|
||
|
||
return {};
|
||
}
|
||
};
|
||
};
|
||
```
|
||
|
||
---
|
||
|
||
## Flow Fields avec Float Positions
|
||
|
||
### Problème : Grid Discrète vs Unités Float
|
||
|
||
```
|
||
Flow Field = grille discrète (tiles entiers)
|
||
Unités = positions float continues
|
||
|
||
Unit pos = (127.34, 89.67) ← Float world space
|
||
Flow Field cell = [127, 89] ← Grid space
|
||
```
|
||
|
||
### Solution : Interpolation Bilinéaire
|
||
|
||
```cpp
|
||
/**
|
||
* @brief Get flow direction at continuous float position
|
||
* @param field Flow field (discrete grid)
|
||
* @param float_pos Unit position (continuous float)
|
||
* @return Interpolated direction vector
|
||
*/
|
||
Vector2 getFlowDirection(FlowField& field, Position float_pos) {
|
||
// Convert float → grid coords
|
||
int x0 = (int)floor(float_pos.x);
|
||
int y0 = (int)floor(float_pos.y);
|
||
int x1 = x0 + 1;
|
||
int y1 = y0 + 1;
|
||
|
||
// Interpolation factors (0.0-1.0)
|
||
float fx = float_pos.x - x0;
|
||
float fy = float_pos.y - y0;
|
||
|
||
// Read 4 neighbor vectors
|
||
Vector2 v00 = field.get(x0, y0);
|
||
Vector2 v10 = field.get(x1, y0);
|
||
Vector2 v01 = field.get(x0, y1);
|
||
Vector2 v11 = field.get(x1, y1);
|
||
|
||
// Bilinear interpolation
|
||
Vector2 v0 = lerp(v00, v10, fx); // Horizontal interpolation
|
||
Vector2 v1 = lerp(v01, v11, fx);
|
||
Vector2 result = lerp(v0, v1, fy); // Vertical interpolation
|
||
|
||
return normalize(result);
|
||
}
|
||
|
||
Vector2 lerp(Vector2 a, Vector2 b, float t) {
|
||
return {
|
||
a.x + (b.x - a.x) * t,
|
||
a.y + (b.y - a.y) * t
|
||
};
|
||
}
|
||
```
|
||
|
||
### Unit Movement with Flow Field
|
||
|
||
```cpp
|
||
/**
|
||
* @brief Update unit position using flow field + steering behaviors
|
||
* @param unit Unit to update (float position, float velocity)
|
||
* @param field Flow field
|
||
* @param delta_time Frame delta time
|
||
*/
|
||
void updateUnitWithFlowField(Unit& unit, FlowField& field, float delta_time) {
|
||
// 1. Read desired direction from flow field (interpolated)
|
||
Vector2 desired_direction = getFlowDirection(field, unit.pos);
|
||
|
||
// 2. Steering behaviors (boids-style)
|
||
Vector2 separation = calculateSeparation(unit); // Avoid other units
|
||
Vector2 cohesion = calculateCohesion(unit); // Stay grouped
|
||
Vector2 alignment = calculateAlignment(unit); // Align with group
|
||
|
||
// 3. Combine (weighted)
|
||
Vector2 steering = desired_direction * 1.0f + // Flow field priority
|
||
separation * 0.8f + // Collision avoidance
|
||
cohesion * 0.3f + // Group cohesion
|
||
alignment * 0.2f; // Direction alignment
|
||
|
||
// 4. Apply velocity
|
||
unit.velocity = normalize(steering) * unit.max_speed;
|
||
unit.pos += unit.velocity * delta_time;
|
||
|
||
// 5. Collision resolution (physics)
|
||
resolveUnitCollisions(unit);
|
||
}
|
||
```
|
||
|
||
### Unit-to-Unit Collisions (Float Space)
|
||
|
||
```cpp
|
||
/**
|
||
* @brief Resolve collisions between units (float positions, circular colliders)
|
||
* @param unit Unit to check collisions for
|
||
*/
|
||
void resolveUnitCollisions(Unit& unit) {
|
||
// Spatial hash for fast neighbor queries
|
||
auto nearby = spatial_hash.query(unit.pos, unit.radius * 3.0f);
|
||
|
||
for (auto& other : nearby) {
|
||
if (other.id == unit.id) continue;
|
||
|
||
Vector2 diff = unit.pos - other.pos;
|
||
float dist = length(diff);
|
||
float min_dist = unit.radius + other.radius;
|
||
|
||
if (dist < min_dist && dist > 0.001f) {
|
||
// Collision detected! Separate units
|
||
Vector2 separation = normalize(diff) * (min_dist - dist) * 0.5f;
|
||
|
||
unit.pos += separation;
|
||
other.pos -= separation;
|
||
|
||
// Velocity damping (elastic bounce)
|
||
float restitution = 0.3f;
|
||
float impact = dot(unit.velocity, normalize(diff));
|
||
|
||
unit.velocity -= normalize(diff) * impact * restitution;
|
||
other.velocity += normalize(diff) * impact * restitution;
|
||
}
|
||
}
|
||
}
|
||
|
||
/**
|
||
* @brief Calculate separation force (boids steering)
|
||
* @param unit Unit to calculate separation for
|
||
* @return Separation vector (away from nearby units)
|
||
*/
|
||
Vector2 calculateSeparation(Unit& unit) {
|
||
const float SEPARATION_RADIUS = 5.0f; // 5m radius
|
||
|
||
Vector2 separation = {0, 0};
|
||
int count = 0;
|
||
|
||
auto nearby = spatial_hash.query(unit.pos, SEPARATION_RADIUS);
|
||
|
||
for (auto& other : nearby) {
|
||
if (other.id == unit.id) continue;
|
||
|
||
Vector2 diff = unit.pos - other.pos;
|
||
float dist = length(diff);
|
||
|
||
if (dist > 0 && dist < SEPARATION_RADIUS) {
|
||
// Force inversely proportional to distance
|
||
separation += normalize(diff) / dist;
|
||
count++;
|
||
}
|
||
}
|
||
|
||
if (count > 0) {
|
||
separation /= count;
|
||
}
|
||
|
||
return separation;
|
||
}
|
||
```
|
||
|
||
### Path Structure
|
||
|
||
```cpp
|
||
struct Path {
|
||
std::vector<Waypoint> waypoints;
|
||
|
||
// Metrics tactiques
|
||
float length; // Distance totale (m)
|
||
float threat_level; // 0.0-1.0 (exposition ennemie)
|
||
float cover_percentage; // % du chemin avec cover
|
||
bool crosses_open_terrain; // Traverse terrain ouvert ?
|
||
bool has_chokepoints; // Contient goulets ?
|
||
|
||
// Metadata
|
||
PathfindingAlgorithm algorithm; // A*, HPA*, ou FLOW_FIELD
|
||
float computation_time_ms; // Temps calcul
|
||
int waypoint_count;
|
||
|
||
// Cover points
|
||
std::vector<Waypoint> cover_points; // Waypoints avec cover
|
||
MovementStyle movement_style; // DIRECT, COVER_TO_COVER, STEALTH
|
||
|
||
// Validation
|
||
bool is_valid;
|
||
int last_validation_frame;
|
||
};
|
||
|
||
struct Waypoint {
|
||
Position pos;
|
||
|
||
// Tactical metadata
|
||
bool has_cover;
|
||
float cover_quality; // 0.0-1.0
|
||
Vector2 cover_direction; // Direction protection
|
||
float threat_level; // Menace à cette position
|
||
|
||
// Movement metadata
|
||
float pause_duration; // Temps pause (cover, observation)
|
||
MovementSpeed speed; // SPRINT, RUN, WALK, CROUCH
|
||
};
|
||
|
||
enum MovementStyle {
|
||
DIRECT, // Ligne droite, rapide
|
||
COVER_TO_COVER, // Pause dans covers
|
||
STEALTH, // Lent, évite détection
|
||
AGGRESSIVE // Rapide, ignore menaces
|
||
};
|
||
```
|
||
|
||
---
|
||
|
||
## Performance Benchmarks & Targets
|
||
|
||
### Targets par Algorithme
|
||
|
||
| Algorithme | Distance | Unités | Target | Acceptable |
|
||
|------------|----------|--------|--------|------------|
|
||
| A* | 50m | 1 | < 2ms | < 5ms |
|
||
| A* | 100m | 1 | < 5ms | < 10ms |
|
||
| HPA* | 500m | 1 | < 5ms | < 10ms |
|
||
| HPA* | 5000m | 1 | < 10ms | < 15ms |
|
||
| Flow Field | 500m | 50 | < 15ms | < 20ms |
|
||
| Flow Field | 500m | 100 | < 20ms | < 30ms |
|
||
| Multi-Path (3) | 100m | 1 | < 10ms | < 15ms |
|
||
|
||
### Budget Frame (60fps = 16.67ms)
|
||
|
||
```
|
||
Total Frame Budget : 16.67ms
|
||
|
||
Distribution :
|
||
- Rendering : 6ms (36%)
|
||
- Physics : 2ms (12%)
|
||
- AI Decisions : 2ms (12%)
|
||
- Pathfinding : 4ms (24%) ← BUDGET
|
||
- Movement : 1ms (6%)
|
||
- Other : 1.67ms (10%)
|
||
|
||
Pathfinding budget : 4ms MAX
|
||
→ ~2 A* paths per frame
|
||
→ ou 1 Flow Field
|
||
→ ou 4 HPA* paths
|
||
```
|
||
|
||
### Optimisations Performance
|
||
|
||
**1. Async Pathfinding**
|
||
|
||
```cpp
|
||
class AsyncPathfinder {
|
||
public:
|
||
std::future<Path> findPathAsync(Position start, Position goal, PathConstraints constraints) {
|
||
return std::async(std::launch::async, [=]() {
|
||
return pathfinder->findPath(start, goal, constraints);
|
||
});
|
||
}
|
||
|
||
void update() {
|
||
// Check completed async requests
|
||
for (auto it = pending_requests.begin(); it != pending_requests.end();) {
|
||
if (it->future.wait_for(std::chrono::milliseconds(0)) == std::future_status::ready) {
|
||
Path path = it->future.get();
|
||
it->callback(path);
|
||
it = pending_requests.erase(it);
|
||
} else {
|
||
++it;
|
||
}
|
||
}
|
||
}
|
||
};
|
||
```
|
||
|
||
**2. Path Pooling**
|
||
|
||
```cpp
|
||
class PathPool {
|
||
public:
|
||
Path* acquire() {
|
||
if (available_paths.empty()) {
|
||
return new Path();
|
||
}
|
||
|
||
Path* path = available_paths.back();
|
||
available_paths.pop_back();
|
||
path->clear();
|
||
return path;
|
||
}
|
||
|
||
void release(Path* path) {
|
||
available_paths.push_back(path);
|
||
}
|
||
|
||
private:
|
||
std::vector<Path*> available_paths;
|
||
};
|
||
```
|
||
|
||
**3. Spatial Hashing**
|
||
|
||
```cpp
|
||
class SpatialPathCache {
|
||
public:
|
||
Path* getCachedPath(Position start, Position goal, float tolerance = 5.0f) {
|
||
// Hash start/goal dans grille spatiale
|
||
CellId cell = hashPosition(start, goal);
|
||
|
||
auto& paths_in_cell = spatial_cache[cell];
|
||
|
||
for (auto& cached : paths_in_cell) {
|
||
if (distance(cached.start, start) < tolerance &&
|
||
distance(cached.goal, goal) < tolerance) {
|
||
|
||
// Valider chemin encore valide
|
||
if (validatePath(cached.path)) {
|
||
return &cached.path;
|
||
}
|
||
}
|
||
}
|
||
|
||
return nullptr; // Pas en cache
|
||
}
|
||
};
|
||
```
|
||
|
||
---
|
||
|
||
## Cas d'Usage Complets
|
||
|
||
### Cas 1 : Infanterie Avance sous Feu
|
||
|
||
```cpp
|
||
// Situation : 10 soldats doivent traverser zone sous feu ennemi
|
||
Position start = squad.getCenter();
|
||
Position objective = {500, 300};
|
||
|
||
// Setup threat map
|
||
ThreatMap threats;
|
||
threats.addThreatSource(enemy_mg.pos, enemy_mg.range, enemy_mg.firepower);
|
||
|
||
// Contraintes : MAX cover, éviter menaces
|
||
PathConstraints infantry_constraints;
|
||
infantry_constraints.threat_weight = 5.0f;
|
||
infantry_constraints.cover_weight = 3.0f;
|
||
infantry_constraints.exposure_weight = 10.0f;
|
||
infantry_constraints.unit_type = INFANTRY;
|
||
infantry_constraints.doctrine = CAUTIOUS;
|
||
|
||
// Génère chemin cover-to-cover
|
||
Path path = pathfinder->findCoverToCoverPath(start, objective, threats, cover_map);
|
||
|
||
// Assigne aux unités
|
||
for (auto& soldier : squad) {
|
||
soldier.setPath(path);
|
||
soldier.movement_style = COVER_TO_COVER;
|
||
}
|
||
|
||
// Résultat :
|
||
// - Chemin zigzague entre covers
|
||
// - Pauses 2-3s dans chaque cover
|
||
// - Évite terrain ouvert
|
||
// - Traverse zone en 45s au lieu de 15s (direct)
|
||
// - 0 pertes au lieu de 50% (direct)
|
||
```
|
||
|
||
### Cas 2 : Tank Assault avec 3 Routes Flanking
|
||
|
||
```cpp
|
||
// Situation : 1 tank doit attaquer position fortifiée
|
||
Position tank_pos = {100, 100};
|
||
Position enemy_bunker = {400, 400};
|
||
|
||
// Contraintes tank
|
||
PathConstraints tank_constraints;
|
||
tank_constraints.threat_weight = 2.0f;
|
||
tank_constraints.terrain_weight = 2.0f; // Évite forêts
|
||
tank_constraints.prefer_roads = true;
|
||
tank_constraints.unit_type = TANK_MEDIUM;
|
||
|
||
// Génère 3 chemins alternatifs
|
||
auto paths = pathfinder->findAllPaths(tank_pos, enemy_bunker, 3, tank_constraints);
|
||
|
||
// Score chemins selon situation tactique
|
||
TacticalScore scores[3];
|
||
for (int i = 0; i < 3; i++) {
|
||
scores[i].threat = paths[i].threat_level;
|
||
scores[i].distance = paths[i].length;
|
||
scores[i].cover = paths[i].cover_percentage;
|
||
scores[i].time = paths[i].length / tank.speed;
|
||
|
||
// Score composite (doctrine agressive)
|
||
scores[i].total =
|
||
scores[i].threat * -0.3f + // Menace pas trop importante
|
||
scores[i].distance * -0.2f + // Distance compte un peu
|
||
scores[i].cover * 0.1f + // Cover bonus mineur
|
||
scores[i].time * -0.4f; // Vitesse PRIORITÉ
|
||
}
|
||
|
||
// Choisit meilleur
|
||
int best = std::max_element(scores, scores+3) - scores;
|
||
tank.setPath(paths[best]);
|
||
|
||
// Résultat :
|
||
// paths[0] : Direct, threat=0.8, time=20s → score=-0.5
|
||
// paths[1] : Flanking gauche, threat=0.4, time=30s → score=-0.3 ✅ CHOISI
|
||
// paths[2] : Flanking droite (forêt), threat=0.2, time=60s → score=-0.8
|
||
```
|
||
|
||
### Cas 3 : 50 Tanks Convergent vers Objectif
|
||
|
||
```cpp
|
||
// Situation : 50 tanks dispersés convergent vers point rally
|
||
Position rally_point = {1000, 1000};
|
||
|
||
// Contraintes communes
|
||
PathConstraints tank_constraints;
|
||
tank_constraints.prefer_roads = true;
|
||
tank_constraints.unit_type = TANK_HEAVY;
|
||
|
||
// Check si flow field viable
|
||
int tanks_with_same_goal = 0;
|
||
for (auto& tank : all_tanks) {
|
||
if (tank.goal == rally_point) {
|
||
tanks_with_same_goal++;
|
||
}
|
||
}
|
||
|
||
if (tanks_with_same_goal >= 10) {
|
||
// Flow Field optimal
|
||
FlowField field = pathfinder->generateFlowField(rally_point, tank_constraints);
|
||
|
||
for (auto& tank : all_tanks) {
|
||
if (tank.goal == rally_point) {
|
||
tank.setFlowField(field); // Partagé!
|
||
}
|
||
}
|
||
|
||
// Performance : 15ms pour 50 tanks au lieu de 50 × 5ms = 250ms
|
||
|
||
} else {
|
||
// Pas assez d'unités, HPA* individuel
|
||
for (auto& tank : all_tanks) {
|
||
Path path = pathfinder->findPath(tank.pos, rally_point, tank_constraints);
|
||
tank.setPath(path);
|
||
}
|
||
}
|
||
```
|
||
|
||
---
|
||
|
||
## Configuration Module
|
||
|
||
### gameconfig.json
|
||
|
||
```json
|
||
{
|
||
"modules": {
|
||
"pathfinding": {
|
||
"enabled": true,
|
||
"frequency": 10,
|
||
|
||
"algorithms": {
|
||
"astar": {
|
||
"max_distance": 100.0,
|
||
"max_iterations": 10000,
|
||
"heuristic": "euclidean"
|
||
},
|
||
|
||
"hierarchical": {
|
||
"cluster_size": 256,
|
||
"levels": 2,
|
||
"cache_size": 1000,
|
||
"rebuild_interval": 300
|
||
},
|
||
|
||
"flow_field": {
|
||
"resolution": 1.0,
|
||
"smooth_radius": 2,
|
||
"local_field_size": 512,
|
||
"cache_duration": 10.0
|
||
}
|
||
},
|
||
|
||
"navmesh": {
|
||
"cell_size": 1.0,
|
||
"cell_height": 0.5,
|
||
"agent_height": 2.0,
|
||
"agent_radius": 1.0,
|
||
"max_slope": 45.0,
|
||
"max_climb": 1.0
|
||
},
|
||
|
||
"performance": {
|
||
"async_pathfinding": true,
|
||
"max_paths_per_frame": 2,
|
||
"path_pool_size": 100,
|
||
"cache_paths": true,
|
||
"cache_size": 500
|
||
},
|
||
|
||
"tactical": {
|
||
"update_threat_map": true,
|
||
"threat_map_resolution": 2.0,
|
||
"cover_detection_radius": 5.0,
|
||
"line_of_sight_checks": true
|
||
},
|
||
|
||
"debug": {
|
||
"visualize_paths": false,
|
||
"visualize_flow_fields": false,
|
||
"visualize_navmesh": false,
|
||
"log_performance": true
|
||
}
|
||
}
|
||
}
|
||
}
|
||
```
|
||
|
||
---
|
||
|
||
## Roadmap Implémentation
|
||
|
||
### Phase 1 : Foundation (2 semaines)
|
||
- [ ] Structure Path, Waypoint, PathConstraints
|
||
- [ ] Interface PathfinderModule complète
|
||
- [ ] A* basique sur grille 64×64
|
||
- [ ] Terrain cost table
|
||
- [ ] Tests unitaires A*
|
||
|
||
### Phase 2 : Weighted A* (1 semaine)
|
||
- [ ] ThreatMap implementation
|
||
- [ ] CoverMap implementation
|
||
- [ ] Weighted cost calculation
|
||
- [ ] PathConstraints integration
|
||
- [ ] Doctrine presets
|
||
|
||
### Phase 3 : Multi-Path (1 semaine)
|
||
- [ ] Penalty-based A* pour divergence
|
||
- [ ] findAllPaths() implementation
|
||
- [ ] Path scoring tactique
|
||
- [ ] Tests flanking scenarios
|
||
|
||
### Phase 4 : Recastnavigation (2 semaines)
|
||
- [ ] NavMesh génération par chunk
|
||
- [ ] Detour queries integration
|
||
- [ ] NavMesh streaming
|
||
- [ ] Dynamic obstacle updates
|
||
- [ ] NavMesh rebuild system
|
||
|
||
### Phase 5 : HPA* (2 semaines)
|
||
- [ ] Cluster graph construction
|
||
- [ ] Intra-cluster path caching
|
||
- [ ] Inter-cluster A* sur abstract graph
|
||
- [ ] Path smoothing
|
||
- [ ] Multi-level hierarchies
|
||
|
||
### Phase 6 : Flow Fields (1 semaine)
|
||
- [ ] Cost field generation
|
||
- [ ] Integration field (Dijkstra inverse)
|
||
- [ ] Flow vector field
|
||
- [ ] Unit steering along field
|
||
- [ ] Field caching
|
||
|
||
### Phase 7 : Optimization (1 semaine)
|
||
- [ ] Async pathfinding
|
||
- [ ] Path pooling
|
||
- [ ] Spatial caching
|
||
- [ ] Performance profiling
|
||
- [ ] Benchmarks validation
|
||
|
||
### Phase 8 : Polish (1 semaine)
|
||
- [ ] Cover-to-cover pathfinding
|
||
- [ ] Flanking position finder
|
||
- [ ] Line of sight queries
|
||
- [ ] Debug visualization
|
||
- [ ] Documentation finalization
|
||
|
||
**Total : ~11 semaines pour système complet**
|
||
|
||
---
|
||
|
||
## Références Techniques
|
||
|
||
### Algorithmes
|
||
- **A***: Hart, P. E.; Nilsson, N. J.; Raphael, B. (1968). "A Formal Basis for the Heuristic Determination of Minimum Cost Paths"
|
||
- **HPA***: Botea, Müller, Schaeffer (2004). "Near Optimal Hierarchical Path-Finding"
|
||
- **Flow Fields**: Elias (2010). "Crowd Path Finding and Steering Using Flow Field Tiles"
|
||
|
||
### Libraries
|
||
- **Recastnavigation**: https://github.com/recastnavigation/recastnavigation
|
||
- **Détails integration**: `src/core/_deps/recastnavigation-src/`
|
||
|
||
### Warfactory Docs
|
||
- `map-system.md` : Chunk system 64×64
|
||
- `systemes-techniques.md` : Architecture multi-échelle
|
||
- `ai-framework.md` : PathfinderModule interface, AI integration
|
||
- `systeme-militaire.md` : Tactical AI, doctrines
|
||
|
||
---
|
||
|
||
## Glossaire
|
||
|
||
- **A*** : Algorithme pathfinding optimal avec heuristique
|
||
- **HPA*** : Hierarchical Pathfinding A*, multi-niveaux abstraction
|
||
- **Flow Field** : Champ vectoriel direction optimale vers goal
|
||
- **NavMesh** : Navigation Mesh, polygones navigables
|
||
- **Dijkstra** : Algorithme shortest path sans heuristique
|
||
- **Threat Map** : Grille valeurs menace ennemie
|
||
- **Cover Map** : Grille positions cover disponibles
|
||
- **Waypoint** : Point passage sur chemin
|
||
- **Constraint** : Contrainte pathfinding (poids, interdictions)
|
||
- **Doctrine** : Preset poids tactiques (aggressive, cautious, etc.)
|
||
- **Cluster** : Zone abstraction pour HPA*
|
||
- **Edge** : Connexion entre clusters HPA*
|
||
- **Integration Field** : Champ coûts cumulés depuis goal (flow fields)
|
||
- **Cost Field** : Champ coûts base terrain (flow fields)
|
||
|
||
---
|
||
|
||
**Ce système hybride offre le meilleur des trois mondes : précision tactique (A*), vitesse longue distance (HPA*), et scaling groupes massifs (Flow Fields).**
|