The regional path planner (RPP) connects the global route planner and the local trajectory planner. It converts the waypoint sequence from the global route planner into a smooth and safe path that avoids obstacles within the sensing range. The local trajectory planner then uses this path to guide the robot.
Inputs:
PoseTree: This library provides the pose frame transform queries.
Route: This message from route planner provides the global guidance for path searching.
Evidence Grid Map: This message from onboard perception shows the distance to obstacles in real time.
Occupancy Map: This map represents the pre-mapped environment occupancy.
Semantic Map: This map contains the human annotated environment context.
Planner Operation Mode: This message from the behavior executor controls the path searching mode.
Outputs:
Regional Path: The smooth and safe path that the trajectory planner uses to guide the robot.
Path Health: This message indicates the status of the regional path solving process and whether a rerouting request is needed.
The regional path planner consists of four major components that are easy to customize and configure:
Problem Formulator: This component defines the path problem based on the robot model, search space representation, cost formulation and waypoint management.
Path Solver: This component solves the path problem using a selected algorithm and searches the optimal regional path for trajectory optimization.
Path Smoother: This component optionally smooths the solved path to make it more friendly for trajectory optimization.
Failure Handler: This component handles any failures that may occur during the path search process. It can provide a fallback path or trigger a rerouting request.
The following diagram shows how these components work together:

Problem Formulator
Path problem formulator helps to define the path problem in a generic way that can be easily configured and used by different path solvers. It consists of four subcomponents:
Robot Model
This subcomponent defines the robot’s properties and motion capabilities. It uses the following information:
Shape: The robot’s shape as a polygon and a list of disks for efficient collision detection.
Motion: The robot’s kinematics as either a point model or a motion primitive model.
Limits: The robot’s constraints and limits such as maximum curvature, etc..
With this information, the robot model can validate state transitions and generate feasible motions for path searching.
Space Discretizer
This subcomponent divides the search space into discrete configurations. It can use two different methods depending on the environment:
Cartesian coordinate: For unstructured space with uniform coverage.
Frenet coordinate: For structured space with a reference path.
Each discrete grid has a unique id for cost caching. The robot model can check the motions within the grids.
Waypoint Manager
This subcomponent manages the waypoints within the search range and identifies the target waypoint for path searching. It performs the following steps:
It chooses a target waypoint from the route by calculating where the route and search boundary cross.
It verifies that the target waypoint is clear of obstacles using the obstacle maps.
If valid, it commits the target waypoint. If not, it either reports a failure or searches for another waypoint to substitute.

Cost Manager
With the robot model and the space discretizer, this subcomponent is to compute the cost based on the navigation objectives.
Cost |
Objective |
---|---|
Travel Distance | Produce shorter path |
Motion | Penalize the unwanted motion segment, e.g., max curvature, lateral acceleration, etc. |
Waypoint Guidance | Encourage the path to follow the guidance of waypoint sequence. |
Path Flickering | Stabilize the paths between consecutive cycles. |
EGM Clearance | Penalize the proximity to the real-time perceived obstacles. |
Semantic Distance | Penalize the proximity to the annotated high-risk regions (e.g., stairs). |
Occupancy Map | Penalize the proximity to the pre-mapped occupancy grid. |
Path Solver
This subcomponent finds the best regional path by using a chosen search algorithm (e.g., A*). It uses the robot model’s motions to explore the search space without a predefined graph. It also stores the cost of each node it visits until it reaches the target waypoint.
Path Smoother
This subcomponent can smooth the solved path as an extra refinement to make the path less jagged and the rotations less sharp.
We can select different smoothers based on the criteria. Some are model-based (e.g., iLQR), which respect the robot constraints but require more computation. Others are for signal denoising (e.g., Savitzky-Golay filter), which are more lightweight but do not ensure feasibility.
Failure Handler
This subcomponent helps the regional path planner deal with blocked routes. It tries these strategies:
Fallback Search: This strategy expands the search space before asking for a rerouting.
Rerouting: If fallback search fails too, this strategy requests a global route search that can find a different way.
The path health and the rerouting request are sent to the behavior executor to work better with other navigation modules.

NvIsaacRegionalPathPlanner
Extension containing regional path planners.
nvidia::isaac::RobotModelConfigLoader
A component that loads the configs for robot model.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Robot Model Type
robot_model_type
The type of robot model to be loaded.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
- name
- lookup_name
- description
- flags
- type
- default
Robot Disks
robot_disks
The disks to approximate the robot shape.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Motion Primitives Poses
motion_primitives_poses
The motion primitives represented as sequences of poses in robot frame
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_CUSTOM
N/A
nvidia::isaac::SpaceDiscretizerConfigLoader
A component that loads the configs for space discretizer.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Space Type
space_type
The type of search space to be discretized.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
- name
- lookup_name
- description
- flags
- type
- default
Cell Size
cell_size
The size of the uniform SE2 grid.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Space Dimensions
space_dimensions
The dimensions of the seach space in [front, rear, left, right].
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_INT32
N/A
- name
- lookup_name
- description
- flags
- type
- default
Heading partition Size
heading_partition_size
The size of heading partitions.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_INT32
N/A
nvidia::isaac::CostComponentConfigLoader
A component that loads the configs for cost component.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Weight
weight
The weight of the cost component.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::TravelDistanceCostConfigLoader
A component that loads the configs for travel distance cost component.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Weight
weight
The weight of the cost component.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::WaypointGuidanceCostConfigLoader
A component that loads the configs for waypoint guidance cost component.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Weight
weight
The weight of the cost component.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Target Offset
target_offset
Offset that the robot should have with respect to the route. Positive means offset to the left of the route in direction of travel.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Bias
bias
Bias to select on what side of the target offset the robot should prefer to drive. Has to be in [-1.0, 1.0]. If equal to -1.0 the robot will prefer to drive on the right, for 1.0 on the left. For 0.0 it is symmetric.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::PathFlickerCostConfigLoader
A component that loads the configs for path flicker cost component.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Weight
weight
The weight of the cost component.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::EgmDistanceCostConfigLoader
A component that loads the configs for Egm distance cost component.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Weight
weight
The weight of the cost component.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Egm Name
egm_name
The name of the EGM input.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
- name
- lookup_name
- description
- flags
- type
- default
Critical Clearance
critical_clearance
The clearance threshold to trigger the critical violation cost.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Comfort Clearance
comfort_clearance
The clearance threshold to trigger the comfort violation cost.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Comfort Violation Cost
comfort_violation_cost
The cost applied when comfort clearance is violated.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::MotionCostConfigLoader
A component that loads the configs for motion cost component.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Weight
weight
The weight of the cost component.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Curvature Cost
curvature_cost
The cost of the curvature.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::NavigableSurfaceCostConfigLoader
A component that loads the configs for navigable surface cost component.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Weight
weight
The weight of the cost component.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::OccupancyMapCostConfigLoader
A component that loads the configs for occupancy map cost component.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Weight
weight
The weight of the cost component.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Hard Constraint Effective Distance
hard_constraint_effective_distance
The distance to robot beyond which the occupancy map is costed as hard constraint.
GXF_PARAMETER_FLAGS_DYNAMIC
GXF_PARAMETER_TYPE_FLOAT64
3.0
- name
- lookup_name
- description
- flags
- type
- default
Critical Clearance
critical_clearance
The critical distance buffer to apply occupancy map cost.
GXF_PARAMETER_FLAGS_DYNAMIC
GXF_PARAMETER_TYPE_FLOAT64
0.1
- name
- lookup_name
- description
- flags
- type
- default
Pessimistic Egm Name
pessimistic_egm_name
The name of the pessimistic EGM to check the occupancy map’s trustiness
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
nvidia::isaac::SemanticDistanceCostConfigLoader
A Component that loads the configs for semantic distance cost component.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Weight
weight
The weight of the cost component.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Region Type
region_type
The semantic region type to which the distance will be calculated.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
- name
- lookup_name
- description
- flags
- type
- default
Avoid Inaccessible Regions
avoid_inaccessible_regions
If true the cost will also be applied to any region marked as ‘inaccessible’.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_BOOL
N/A
- name
- lookup_name
- description
- flags
- type
- default
Critical Clearance
critical_clearance
The clearance threshold to trigger the critical violation cost.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Comfort Clearance
comfort_clearance
The clearance threshold to trigger the comfort violation cost.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Comfort Violation Cost
comfort_violation_cost
The cost applied when comfort clearance is violated.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::SumCostConfigLoader
A Component that loads the configs for sum cost component.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Managed Costs
managed_costs
The managed costs to be summed.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::HeuristicConfigLoader
A component that loads the configs for the heuristics.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Heuristic Type
heuristic_type
The name of the heuristic.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
- name
- lookup_name
- description
- flags
- type
- default
Weight
weight
The weight of the heuristic.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::PathSolverConfigLoader
A component that loads the configs for the path solver.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Target Waypoint Reach Tolerance
target_waypoint_reach_tolerance
The tolerance to decide if the target waypoint has been reached during path search.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::RegionalPathConfigLoader
A component that loads the configs for regional path planner.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Enabled
enabled
Flags controls if the regional path planner is enabled.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_BOOL
N/A
- name
- lookup_name
- description
- flags
- type
- default
Robot Model
robot_model
The handle to the robot model config.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Space Discretizer
space_discretizer
The handle to the space discretizer config.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Cost Tree Root
cost_tree_root
The handle to the root of the cost component tree.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Heuristic
heuristic
The handle to the heuristic config.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Path Solver
path_solver
The handle to the path solver config.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::RegionalPathDebugVisualizer
A component that visualizes the debug data for regional path planner.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Sight
sight
A sight transmitter handle for regional path planner debug visualization.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Operation Mode Text Width
operation_mode_text_size
The size of the text visualization as it appears in sight.
GXF_PARAMETER_FLAGS_DYNAMIC
GXF_PARAMETER_TYPE_FLOAT64
18.0
- name
- lookup_name
- description
- flags
- type
- default
Operation Mode Text Row
operation_mode_text_row
The row where the text visualization is displayed in sight.
GXF_PARAMETER_FLAGS_DYNAMIC
GXF_PARAMETER_TYPE_INT32
10
- name
- lookup_name
- description
- flags
- type
- default
Operation Mode Text Col
operation_mode_text_col
The column where the text visualization is displayed in sight.
GXF_PARAMETER_FLAGS_DYNAMIC
GXF_PARAMETER_TYPE_INT32
10
- name
- lookup_name
- description
- flags
- type
- default
Operation Mode Base Text
operation_mode_text_base
The base text name for the value that changes
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
nvidia::isaac::MessageCache >
A component that handles the EGM input.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Incoming message
rx_message
The channel for the input message.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming message max timeout
max_timeout
The max timeout for the input message. Set inf to skip timeout check
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::MessageCache
A component that handles the semantic regions input.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Incoming message
rx_message
The channel for the input message.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming message max timeout
max_timeout
The max timeout for the input message. Set inf to skip timeout check
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::MessageCache
A component that handles the maneuver input.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Incoming message
rx_message
The channel for the input message.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming message max timeout
max_timeout
The max timeout for the input message. Set inf to skip timeout check
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::MessageCache
A component that handles the planner operation mode input.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Incoming message
rx_message
The channel for the input message.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming message max timeout
max_timeout
The max timeout for the input message. Set inf to skip timeout check
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::WorldStateGenerator
A component that generates the world state for regional path planner.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Atlas
atlas
Link to Atlas.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Distance Maps
distance_maps
The group of incoming distance maps used for regional path planning.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming maneuver message containing the planning specifications
maneuver
The input channel for the maneuver.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Static Frame
static_frame
The static reference frame for computing transforms between different timestamps.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Planner Frame
planner_frame
Planner frame for the generated path.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Robot Frame
robot_frame
Robot frame for the robot.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming planner operation mode
planner_operation_mode
The input channel for planner operation mode.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Semantic Map Accessor
semantic_map_accessor
Handle to semantic map accessor.
GXF_PARAMETER_FLAGS_OPTIONAL
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::RegionalPathSearcher
A component that searches the regional path based on the world state.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Config Loader
config_loader
The component that loads the configs for regional path searcher.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::RegionalPathMetrics
A component that records the internal metrics for regional path planner.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Search Failure Count
search_failure_count
Metric component to count the path search failures.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Path Deviation
path_deviation_sum
Metric component to sum the path deviation between two consecutive cycles.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Path Clearance
path_clearance_min
Metric component to compute the minimum obstacle clearance.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Path Curvature
path_curvature_max
Metric component to compute the maximum curvature.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::RegionalPathPlanner
A codelet that uses the regional path planner to output a path.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Atlas
atlas
Link to Atlas
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Host Memory Allocator
allocator
The memory allocator used for host memory allocation.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Output Regional Path
tx_path
Output channel where the output path of the regional path planner is transmitted.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Output Planner Health
tx_path_planner_health
Output channel where the health state of the regional path planner is transmitted.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
World State Generator
world_state_generator
The component that generates the world state for regional path planner.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Nominal Searcher
nominal_searcher
The component that searches the regional path using nominal configs.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Fallback Searcher
fallback_searcher
The component that searches the regional path using fallback configs.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Metrics Recorder
metrics_recorder
The component that records the internal metrics for regional path planner.
GXF_PARAMETER_FLAGS_OPTIONAL
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Debug Visualizer
debug_visualizer
The component that visualizes the debug data for regional path planner.
GXF_PARAMETER_FLAGS_OPTIONAL
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Allowed Search Failure Count
allowed_search_failure_count
The allowed search failure count before reporting nominal search failure.
GXF_PARAMETER_FLAGS_DYNAMIC
GXF_PARAMETER_TYPE_INT32
5