While the regional path planner manages lateral constraints, the speed decision maker handles longitudinal constraints that can be divided into two main categories:
Static environment rules: speed recommendations around regions of interest, like stairs, entrance, ramps, annotated high-risk areas, etc..
Dynamic environment interactions: moving obstacles, automatic doors, etc.
By taking all the longitudinal constraints into account, speed decision maker can provide convex speed directives for the trajectory planner to optimize.
Inputs:
Ego Motion: The message contains the robot’s motion state (e.g., speed, acceleration. etc.).
Regional Path: The smooth path produced by the regional path planner.
Evidence Grid Map: The message from onboard perception shows the real-time obstacle clearance.
Semantic Map: The map contains the human annotated environment context.
Outputs:
Speed Directive: The message that contains various speed directives (e.g., speed zone, stopping fence, etc.) for trajectory optimization.
The speed decision maker is divided into three main components:
Speed Problem Formulator: A list of reasoners collecting constraints from both static environment rules and dynamic environment interactions to formulate the decision making problem.
Speed Solver: Solves the formulated problem and makes the optimal decisions for environment interactions.
Speed Directive Generator: Transforms the speed decisions into directives that the trajectory planner can easily consume.
The following diagram shows how these components work together:

Semantic Region Reasoner
The SemanticRegionReasoner is a module designed to identify high-risk semantic regions, such as stairs, entrances, etc., that may pose a collision risk along a planned path. It generates cautious speed zones around these regions to help mitigate the risk of collision.
Listing 1 Adding SemanticRegionReasoner for STAIRS
- name: stair_reasoner
type: nvidia::isaac::SemanticRegionReasonerConfigLoader
parameters:
type_name: kSemanticRegion
semantic_region_type: STAIRS # High-risk semantic region type
max_distance_to_region: 3.0 # Maximum distance to produce speed zones
max_abs_speed: 0.5 # Maximum speed allowed when navigate through regions

Path Clearance Reasoner
The PathClearanceReasoner is a module designed to ensure obstacle clearance along the planned path and generate cautious speed zones around nearby obstacles to mitigate the risk of collision.
As the robot moves along the planned path, the PathClearanceReasoner continually assesses the clearance of obstacles and generates speed zones around those that are identified as being in close proximity to the robot. This helps to ensure that the robot safely avoids obstacles and operates smoothly.
Listing 2 Adding PathClearanceReasoner for an obstacle distance map
- name: obstacle_clearance_reasoner
type: nvidia::isaac::PathClearanceReasonerConfigLoader
parameters:
type_name: kPathClearance
distance_map_name: obstacle_distance_map_input # Obstacle distance map source
max_clearance_to_obstacle: # Maximum obstacle clearance to trigger speed zone
max_clearance_speed: 1.1 # Desired speed at the maximum obstacle clearance
speed_zone_arc_length_buffer: 1.0 # Distance buffer to slow down robot earlier

NvIsaacSpeedDecisionMaker
Extension containing speed decision maker.
nvidia::isaac::SpeedReasonerConfigLoader
A base component that loads the config for speed reasoners.
Parameters:
nvidia::isaac::SemanticRegionReasonerConfigLoader
A component that loads the config for semantic region reasoners.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Type Name
type_name
The reasoner type name.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
- name
- lookup_name
- description
- flags
- type
- default
Semantic Region Type
semantic_region_type
The interested semantic region type.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
- name
- lookup_name
- description
- flags
- type
- default
Max Distance to semantic regions.
max_distance_to_region
The distance to check if a semantic region needs to be considered for speed reasoning.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Max Absolute Speed
max_abs_speed
The maximum absolute speed when moving around the regions.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Speed Zone Duration
speed_zone_duration
The effective time duration of the speed zones generated for the regions.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::PathClearanceReasonerConfigLoader
A component that loads the config for path clearance reasoners.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Type Name
type_name
The reasoner type name.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
- name
- lookup_name
- description
- flags
- type
- default
Distance Map Name
distance_map_name
The name of the distance map to be used for clearance query.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
- name
- lookup_name
- description
- flags
- type
- default
Max Clearance to Obstacle
max_clearance_to_obstacle
The maximum obstacle clearance to trigger speed zone.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Max Clearance Speed
max_clearance_speed
The desired speed at the maximum obstacle clearance.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Clearance Query Step Size
clearance_query_step_size
The step size to sample the regional path for clearance query.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Speed Zone Arc Length Buffer
speed_zone_arc_length_buffer
The arc length buffer added to the speed zone, so the robot can slow down earlier.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::MessageCache
A component that handles the composite message 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::SpeedWorldStateGenerator
A component that generates the world state for speed decision maker.
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
Speed Frame
speed_frame
Speed frame for the generated speed directives.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Robot Frame
robot_frame
The frame for the robot.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming Regional Path
regional_path
The input channel for the path planned by regional path planner.
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
Odometry
odometry
The input channel for the odometry.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming Optimistic Obstacle Distance Map
optimistic_distance_map
The input channel for the optimistic obstacle distance map.
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.
GXF_PARAMETER_FLAGS_OPTIONAL
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::SpeedProblemConfigLoader
A component that loads the config for speed problem formulator.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Speed Reasoners
speed_reasoners
The handle to the speed reasoners config.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::SpeedDecisionDebugVisualizer
A component that generates the world state for speed decision maker.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Sight Speed Zone
sight_speed_zone
A sight transmitter handle for speed zone directive visualization.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::SpeedDecisionMaker
A codelet that uses the speed decision maker to output speed directives.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
World State Generator
world_state_generator
The component that generates the world state for speed decision maker.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Speed Problem Config Loader
speed_problem_config_loader
The component that loads the speed problem configs for speed decision maker.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Output Speed Directive
tx_speed_directive
Output channel where the output speed directives is transmitted.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Debug Visualizer
debug_visualizer
The component that visualizes the speed decision debug.
GXF_PARAMETER_FLAGS_OPTIONAL
GXF_PARAMETER_TYPE_HANDLE
N/A