Speed Decision Maker

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:

sdm_diagram.png

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

Copy
Copied!
            

- 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


stair_speed.png


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

Copy
Copied!
            

- 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


clearance_speed.png


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

Type Name

lookup_name

type_name

description

The reasoner type name.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

name

Semantic Region Type

lookup_name

semantic_region_type

description

The interested semantic region type.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

name

Max Distance to semantic regions.

lookup_name

max_distance_to_region

description

The distance to check if a semantic region needs to be considered for speed reasoning.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Max Absolute Speed

lookup_name

max_abs_speed

description

The maximum absolute speed when moving around the regions.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Speed Zone Duration

lookup_name

speed_zone_duration

description

The effective time duration of the speed zones generated for the regions.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::PathClearanceReasonerConfigLoader

A component that loads the config for path clearance reasoners.

Parameters:

name

Type Name

lookup_name

type_name

description

The reasoner type name.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

name

Distance Map Name

lookup_name

distance_map_name

description

The name of the distance map to be used for clearance query.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

name

Max Clearance to Obstacle

lookup_name

max_clearance_to_obstacle

description

The maximum obstacle clearance to trigger speed zone.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Max Clearance Speed

lookup_name

max_clearance_speed

description

The desired speed at the maximum obstacle clearance.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Clearance Query Step Size

lookup_name

clearance_query_step_size

description

The step size to sample the regional path for clearance query.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Speed Zone Arc Length Buffer

lookup_name

speed_zone_arc_length_buffer

description

The arc length buffer added to the speed zone, so the robot can slow down earlier.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::MessageCache

A component that handles the composite message input.

Parameters:

name

Incoming message

lookup_name

rx_message

description

The channel for the input message.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Incoming message max timeout

lookup_name

max_timeout

description

The max timeout for the input message. Set inf to skip timeout check

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::SpeedWorldStateGenerator

A component that generates the world state for speed decision maker.

Parameters:

name

Atlas

lookup_name

atlas

description

Link to Atlas.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Speed Frame

lookup_name

speed_frame

description

Speed frame for the generated speed directives.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Robot Frame

lookup_name

robot_frame

description

The frame for the robot.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Incoming Regional Path

lookup_name

regional_path

description

The input channel for the path planned by regional path planner.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Incoming maneuver message containing the planning specifications

lookup_name

maneuver

description

The input channel for the maneuver.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Odometry

lookup_name

odometry

description

The input channel for the odometry.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Incoming Optimistic Obstacle Distance Map

lookup_name

optimistic_distance_map

description

The input channel for the optimistic obstacle distance map.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Semantic Map Accessor

lookup_name

semantic_map_accessor

description

Handle to semantic map.

flags

GXF_PARAMETER_FLAGS_OPTIONAL

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::SpeedProblemConfigLoader

A component that loads the config for speed problem formulator.

Parameters:

name

Speed Reasoners

lookup_name

speed_reasoners

description

The handle to the speed reasoners config.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::SpeedDecisionDebugVisualizer

A component that generates the world state for speed decision maker.

Parameters:

name

Sight Speed Zone

lookup_name

sight_speed_zone

description

A sight transmitter handle for speed zone directive visualization.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::SpeedDecisionMaker

A codelet that uses the speed decision maker to output speed directives.

Parameters:

name

World State Generator

lookup_name

world_state_generator

description

The component that generates the world state for speed decision maker.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Speed Problem Config Loader

lookup_name

speed_problem_config_loader

description

The component that loads the speed problem configs for speed decision maker.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Output Speed Directive

lookup_name

tx_speed_directive

description

Output channel where the output speed directives is transmitted.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Debug Visualizer

lookup_name

debug_visualizer

description

The component that visualizes the speed decision debug.

flags

GXF_PARAMETER_FLAGS_OPTIONAL

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

© Copyright 2018-2023, NVIDIA Corporation. Last updated on Oct 23, 2023.