Configuration ============= All global path planner parameters are configured in the ``all_settings`` package. The global planner shares most settings with the local planner but uses different values optimized for full-track optimization. Settings Structure ------------------ The global planner uses ``GlobalOptSettings`` from ``all_settings/all_settings/all_settings.py``: .. code-block:: python class GlobalOptSettings(metaclass=Settings): """Settings for global path planning""" N: int = 100 solver: str = 'ipopt' car_params: dict = {'l_r': 1.58/2, 'l_f': 1.58/2, 'm': 1.} bbox: dict = {'l': 2.7+0.5, 'w': 1.6+0.5} DF_MAX: float = 0.5 ACC_MIN: float = -4.5 ACC_MAX_FN: Union[float, Function] = 2.5 DF_DOT_MAX: float = 1.0 V_MIN: float = 0.0 V_MAX: float = 8.0 FRIC_MAX: float = 7.0 write_to_file: bool = True N_CONES_PER_POINT: int = 4 Key Differences from Local Planner ----------------------------------- N (Number of Waypoints) ~~~~~~~~~~~~~~~~~~~~~~~ **Global:** ``100`` vs **Local:** ``10`` The global planner uses 10× more waypoints to cover the entire track. This is the primary difference between the two planners. **Impact:** - Covers full lap distance (100-200m) - Much larger optimization problem (700 variables vs 70) - Longer solve time (1-5 seconds vs 60-180ms) **Tuning guidance:** - Increase for very large tracks (>200m lap length) - Decrease for smaller tracks or faster computation - Typical range: 80-150 waypoints V_MAX ~~~~~ **Global:** ``8.0`` m/s vs **Local:** ``10.0`` m/s The global planner uses a slightly lower maximum velocity for safety and reliability. **Rationale:** - More conservative for multi-lap racing - Reduces risk of loss of control - Easier for solver to find feasible solutions **Tuning guidance:** - Can increase to 10-12 m/s for more aggressive racing - Decrease to 5-6 m/s for testing or tight tracks bbox (Bounding Box) ~~~~~~~~~~~~~~~~~~~ **Global:** ``{'l': 3.2, 'w': 2.1}`` vs **Local:** ``{'l': 2.7, 'w': 1.6}`` The global planner adds safety margin (0.5m) to the vehicle dimensions for cone avoidance. **Rationale:** - Accounts for state estimation uncertainty - Provides clearance for cone positioning errors - More conservative for repeated lap execution write_to_file ~~~~~~~~~~~~~ **Global:** ``True`` vs **Local:** ``False`` The global planner is configured to save results to file by default (though this feature may not be actively used). N_CONES_PER_POINT ~~~~~~~~~~~~~~~~~ **Global only:** ``4`` **Description:** Number of nearest cones to consider for collision avoidance at each waypoint. **Impact:** - More cones = better safety but more constraints - Fewer cones = faster solve but potential collisions **Note:** Cone avoidance constraints may be disabled in current implementation. Optimization Parameters ----------------------- These parameters are identical to the local planner but documented here for completeness: solver ~~~~~~ **Type:** ``str`` **Default:** ``'ipopt'`` **Description:** NLP solver to use. IPOPT is standard. car_params ~~~~~~~~~~ **Type:** ``dict`` **Default:** ``{'l_r': 0.79, 'l_f': 0.79, 'm': 1.0}`` **Description:** Vehicle parameters for bicycle dynamics. - ``l_r``: Rear wheelbase (0.79m) - ``l_f``: Front wheelbase (0.79m) - ``m``: Mass (1.0 kg, placeholder) Constraint Limits ----------------- DF_MAX ~~~~~~ **Type:** ``float`` **Default:** ``0.5`` radians (±28.6°) **Description:** Maximum steering angle. Same as local planner. ACC_MIN ~~~~~~~ **Type:** ``float`` **Default:** ``-4.5`` m/s² **Description:** Maximum braking acceleration. Same as local planner. ACC_MAX_FN ~~~~~~~~~~ **Type:** ``float`` or ``Function`` **Default:** ``2.5`` m/s² **Description:** Maximum forward acceleration. Same as local planner. Can be constant or velocity-dependent function. DF_DOT_MAX ~~~~~~~~~~ **Type:** ``float`` **Default:** ``1.0`` rad/s **Description:** Maximum steering rate. Same as local planner. V_MIN ~~~~~ **Type:** ``float`` **Default:** ``0.0`` m/s **Description:** Minimum velocity (no reverse). Same as local planner. FRIC_MAX ~~~~~~~~ **Type:** ``float`` or ``Function`` **Default:** ``7.0`` m/s² (~0.7g) **Description:** Friction circle limit (combined acceleration). Same as local planner. Solver Configuration -------------------- The global planner uses similar IPOPT settings as the local planner: .. code-block:: python DEFAULT_SOPTS = { 'ipopt': { 'ipopt.linear_solver': 'ma57', 'expand': True, } } **Key differences:** - No custom tolerances (uses IPOPT defaults) - May require more iterations due to problem size - Warm-starting not available (no previous solution) **Linear solver options:** - ``ma27``: Good general-purpose solver - ``ma57``: Better for large sparse problems (recommended) - ``ma86``, ``ma97``: Modern alternatives - ``mumps``: Open-source option (slower) The HSL linear solvers (ma27, ma57, ma86, ma97) require separate installation but provide significantly better performance for large problems. ROS Topics ---------- **Subscribed Topics:** .. list-table:: :widths: 40 30 30 :header-rows: 1 * - Topic - Type - Description * - ``/slam/map/global`` - feb_msgs/Map - Complete track map (triggers optimization) * - ``/slam/state`` - feb_msgs/State - Current vehicle state **Published Topics:** .. list-table:: :widths: 40 30 30 :header-rows: 1 * - Topic - Type - Description * - ``/path/global`` - feb_msgs/FebPath - Optimized global trajectory (full lap) * - ``/path/finished`` - std_msgs/Bool - Signals path is ready (set to True) * - ``/path/global/viz`` - sensor_msgs/PointCloud - Path visualization Example Configurations ---------------------- Standard Racing ~~~~~~~~~~~~~~~ .. code-block:: python N = 100 # Full track coverage V_MAX = 8.0 # Conservative speed ACC_MAX_FN = 2.5 # Moderate acceleration FRIC_MAX = 7.0 # Good tire grip DF_DOT_MAX = 1.0 # Standard steering rate Aggressive Racing ~~~~~~~~~~~~~~~~~ .. code-block:: python N = 100 # Full track coverage V_MAX = 10.0 # Higher speed limit ACC_MAX_FN = 3.0 # Strong acceleration FRIC_MAX = 9.0 # High-performance tires DF_DOT_MAX = 1.2 # Faster steering Large Track ~~~~~~~~~~~ .. code-block:: python N = 150 # More waypoints for longer track V_MAX = 10.0 # Higher speeds on long straights ACC_MAX_FN = 2.5 # Standard acceleration FRIC_MAX = 7.0 # Standard grip DF_DOT_MAX = 1.0 # Standard steering Technical Track ~~~~~~~~~~~~~~~ .. code-block:: python N = 100 # Standard coverage V_MAX = 6.0 # Lower speed for tight corners ACC_MAX_FN = 2.0 # Moderate power FRIC_MAX = 8.0 # Need good cornering DF_DOT_MAX = 1.2 # Quick direction changes Performance Tuning ------------------ Reducing Solve Time ~~~~~~~~~~~~~~~~~~~ If the global planner takes too long (>10 seconds): 1. **Reduce N**: Try 80 or 90 waypoints 2. **Relax tolerances**: Increase ``acceptable_tol`` to 1e-1 3. **Disable cone constraints**: Remove collision avoidance (if implemented) 4. **Use better linear solver**: Switch from mumps to ma57 Improving Path Quality ~~~~~~~~~~~~~~~~~~~~~~ If the path is too conservative or doesn't use full track width: 1. **Relax track bounds**: Increase allowed range for ``t`` parameter 2. **Increase FRIC_MAX**: Allow more aggressive cornering 3. **Adjust ACC_MAX**: Allow more acceleration/braking 4. **Check cone ordering**: Verify boundaries are correct Solver Failures ~~~~~~~~~~~~~~~ If the optimization fails to converge: 1. **Check cone ordering**: Bad ordering → infeasible problem 2. **Relax constraints**: Temporarily increase limits 3. **Improve initial guess**: Use local path as warm-start 4. **Reduce problem size**: Decrease N to 80 or 60 5. **Use WORHP or SNOPT**: Alternative solvers (require licenses) Debugging --------- To enable verbose output from the solver: .. code-block:: python solver_opts = { 'ipopt.print_level': 5, # Detailed output 'print_time': 1, # Show timing } To save optimization data: .. code-block:: python write_to_file: bool = True Visualization ~~~~~~~~~~~~~ View the global path in RViz: 1. Add **PointCloud** display 2. Set topic to ``/path/global/viz`` 3. Adjust point size for visibility The path should form a smooth closed loop around the track. If it's jagged or crosses boundaries, optimization or cone ordering has failed. Comparison with MPC Settings ----------------------------- Some parameters should be coordinated between the global planner and MPC: .. list-table:: :widths: 30 35 35 :header-rows: 1 * - Parameter - Global Planner - MPC Controller * - Vehicle params (L_f, L_r) - Must match - Must match * - V_MAX - 8.0 m/s (conservative) - 10.0 m/s (allows flexibility) * - ACC_MIN/MAX - 2.5 / -4.5 m/s² - 3.0 / -5.0 m/s² (more aggressive) * - DF_MAX - Must match - Must match * - FRIC_MAX - 7.0 m/s² - Not used by MPC The MPC limits can be slightly more aggressive than the path planner since the MPC operates in closed-loop with state feedback.