Regional Path Planner

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:

rpp_diagram.png

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.

wp_manager.png


Cost Manager

With the robot model and the space discretizer, this subcomponent is to compute the cost based on the navigation objectives.

Table 1 Cost Components and 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.

fallback_search.png


NvIsaacRegionalPathPlanner

Extension containing regional path planners.

nvidia::isaac::RobotModelConfigLoader

A component that loads the configs for robot model.

Parameters:

name

Robot Model Type

lookup_name

robot_model_type

description

The type of robot model to be loaded.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

name

Robot Disks

lookup_name

robot_disks

description

The disks to approximate the robot shape.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Motion Primitives Poses

lookup_name

motion_primitives_poses

description

The motion primitives represented as sequences of poses in robot frame

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_CUSTOM

default

N/A

nvidia::isaac::SpaceDiscretizerConfigLoader

A component that loads the configs for space discretizer.

Parameters:

name

Space Type

lookup_name

space_type

description

The type of search space to be discretized.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

name

Cell Size

lookup_name

cell_size

description

The size of the uniform SE2 grid.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Space Dimensions

lookup_name

space_dimensions

description

The dimensions of the seach space in [front, rear, left, right].

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_INT32

default

N/A

name

Heading partition Size

lookup_name

heading_partition_size

description

The size of heading partitions.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_INT32

default

N/A

nvidia::isaac::CostComponentConfigLoader

A component that loads the configs for cost component.

Parameters:

name

Weight

lookup_name

weight

description

The weight of the cost component.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::TravelDistanceCostConfigLoader

A component that loads the configs for travel distance cost component.

Parameters:

name

Weight

lookup_name

weight

description

The weight of the cost component.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::WaypointGuidanceCostConfigLoader

A component that loads the configs for waypoint guidance cost component.

Parameters:

name

Weight

lookup_name

weight

description

The weight of the cost component.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Target Offset

lookup_name

target_offset

description

Offset that the robot should have with respect to the route. Positive means offset to the left of the route in direction of travel.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Bias

lookup_name

bias

description

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.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::PathFlickerCostConfigLoader

A component that loads the configs for path flicker cost component.

Parameters:

name

Weight

lookup_name

weight

description

The weight of the cost component.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::EgmDistanceCostConfigLoader

A component that loads the configs for Egm distance cost component.

Parameters:

name

Weight

lookup_name

weight

description

The weight of the cost component.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Egm Name

lookup_name

egm_name

description

The name of the EGM input.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

name

Critical Clearance

lookup_name

critical_clearance

description

The clearance threshold to trigger the critical violation cost.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Comfort Clearance

lookup_name

comfort_clearance

description

The clearance threshold to trigger the comfort violation cost.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Comfort Violation Cost

lookup_name

comfort_violation_cost

description

The cost applied when comfort clearance is violated.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::MotionCostConfigLoader

A component that loads the configs for motion cost component.

Parameters:

name

Weight

lookup_name

weight

description

The weight of the cost component.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Curvature Cost

lookup_name

curvature_cost

description

The cost of the curvature.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::NavigableSurfaceCostConfigLoader

A component that loads the configs for navigable surface cost component.

Parameters:

name

Weight

lookup_name

weight

description

The weight of the cost component.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::OccupancyMapCostConfigLoader

A component that loads the configs for occupancy map cost component.

Parameters:

name

Weight

lookup_name

weight

description

The weight of the cost component.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Hard Constraint Effective Distance

lookup_name

hard_constraint_effective_distance

description

The distance to robot beyond which the occupancy map is costed as hard constraint.

flags

GXF_PARAMETER_FLAGS_DYNAMIC

type

GXF_PARAMETER_TYPE_FLOAT64

default

3.0

name

Critical Clearance

lookup_name

critical_clearance

description

The critical distance buffer to apply occupancy map cost.

flags

GXF_PARAMETER_FLAGS_DYNAMIC

type

GXF_PARAMETER_TYPE_FLOAT64

default

0.1

name

Pessimistic Egm Name

lookup_name

pessimistic_egm_name

description

The name of the pessimistic EGM to check the occupancy map’s trustiness

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

nvidia::isaac::SemanticDistanceCostConfigLoader

A Component that loads the configs for semantic distance cost component.

Parameters:

name

Weight

lookup_name

weight

description

The weight of the cost component.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Region Type

lookup_name

region_type

description

The semantic region type to which the distance will be calculated.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

name

Avoid Inaccessible Regions

lookup_name

avoid_inaccessible_regions

description

If true the cost will also be applied to any region marked as ‘inaccessible’.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_BOOL

default

N/A

name

Critical Clearance

lookup_name

critical_clearance

description

The clearance threshold to trigger the critical violation cost.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Comfort Clearance

lookup_name

comfort_clearance

description

The clearance threshold to trigger the comfort violation cost.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Comfort Violation Cost

lookup_name

comfort_violation_cost

description

The cost applied when comfort clearance is violated.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::SumCostConfigLoader

A Component that loads the configs for sum cost component.

Parameters:

name

Managed Costs

lookup_name

managed_costs

description

The managed costs to be summed.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::HeuristicConfigLoader

A component that loads the configs for the heuristics.

Parameters:

name

Heuristic Type

lookup_name

heuristic_type

description

The name of the heuristic.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

name

Weight

lookup_name

weight

description

The weight of the heuristic.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::PathSolverConfigLoader

A component that loads the configs for the path solver.

Parameters:

name

Target Waypoint Reach Tolerance

lookup_name

target_waypoint_reach_tolerance

description

The tolerance to decide if the target waypoint has been reached during path search.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::RegionalPathConfigLoader

A component that loads the configs for regional path planner.

Parameters:

name

Enabled

lookup_name

enabled

description

Flags controls if the regional path planner is enabled.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_BOOL

default

N/A

name

Robot Model

lookup_name

robot_model

description

The handle to the robot model config.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Space Discretizer

lookup_name

space_discretizer

description

The handle to the space discretizer config.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Cost Tree Root

lookup_name

cost_tree_root

description

The handle to the root of the cost component tree.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Heuristic

lookup_name

heuristic

description

The handle to the heuristic config.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Path Solver

lookup_name

path_solver

description

The handle to the path solver config.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::RegionalPathDebugVisualizer

A component that visualizes the debug data for regional path planner.

Parameters:

name

Sight

lookup_name

sight

description

A sight transmitter handle for regional path planner debug visualization.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Operation Mode Text Width

lookup_name

operation_mode_text_size

description

The size of the text visualization as it appears in sight.

flags

GXF_PARAMETER_FLAGS_DYNAMIC

type

GXF_PARAMETER_TYPE_FLOAT64

default

18.0

name

Operation Mode Text Row

lookup_name

operation_mode_text_row

description

The row where the text visualization is displayed in sight.

flags

GXF_PARAMETER_FLAGS_DYNAMIC

type

GXF_PARAMETER_TYPE_INT32

default

10

name

Operation Mode Text Col

lookup_name

operation_mode_text_col

description

The column where the text visualization is displayed in sight.

flags

GXF_PARAMETER_FLAGS_DYNAMIC

type

GXF_PARAMETER_TYPE_INT32

default

10

name

Operation Mode Base Text

lookup_name

operation_mode_text_base

description

The base text name for the value that changes

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

nvidia::isaac::MessageCache >

A component that handles the EGM 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::MessageCache

A component that handles the semantic regions 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::MessageCache

A component that handles the maneuver 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::MessageCache

A component that handles the planner operation mode 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::WorldStateGenerator

A component that generates the world state for regional path planner.

Parameters:

name

Atlas

lookup_name

atlas

description

Link to Atlas.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Distance Maps

lookup_name

distance_maps

description

The group of incoming distance maps used for regional path planning.

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

Static Frame

lookup_name

static_frame

description

The static reference frame for computing transforms between different timestamps.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Planner Frame

lookup_name

planner_frame

description

Planner frame for the generated path.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Robot Frame

lookup_name

robot_frame

description

Robot frame for the robot.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Incoming planner operation mode

lookup_name

planner_operation_mode

description

The input channel for planner operation mode.

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 accessor.

flags

GXF_PARAMETER_FLAGS_OPTIONAL

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::RegionalPathSearcher

A component that searches the regional path based on the world state.

Parameters:

name

Config Loader

lookup_name

config_loader

description

The component that loads the configs for regional path searcher.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::RegionalPathMetrics

A component that records the internal metrics for regional path planner.

Parameters:

name

Search Failure Count

lookup_name

search_failure_count

description

Metric component to count the path search failures.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Path Deviation

lookup_name

path_deviation_sum

description

Metric component to sum the path deviation between two consecutive cycles.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Path Clearance

lookup_name

path_clearance_min

description

Metric component to compute the minimum obstacle clearance.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Path Curvature

lookup_name

path_curvature_max

description

Metric component to compute the maximum curvature.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::RegionalPathPlanner

A codelet that uses the regional path planner to output a path.

Parameters:

name

Atlas

lookup_name

atlas

description

Link to Atlas

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Host Memory Allocator

lookup_name

allocator

description

The memory allocator used for host memory allocation.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Output Regional Path

lookup_name

tx_path

description

Output channel where the output path of the regional path planner is transmitted.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Output Planner Health

lookup_name

tx_path_planner_health

description

Output channel where the health state of the regional path planner is transmitted.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

World State Generator

lookup_name

world_state_generator

description

The component that generates the world state for regional path planner.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Nominal Searcher

lookup_name

nominal_searcher

description

The component that searches the regional path using nominal configs.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Fallback Searcher

lookup_name

fallback_searcher

description

The component that searches the regional path using fallback configs.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Metrics Recorder

lookup_name

metrics_recorder

description

The component that records the internal metrics for regional path planner.

flags

GXF_PARAMETER_FLAGS_OPTIONAL

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Debug Visualizer

lookup_name

debug_visualizer

description

The component that visualizes the debug data for regional path planner.

flags

GXF_PARAMETER_FLAGS_OPTIONAL

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Allowed Search Failure Count

lookup_name

allowed_search_failure_count

description

The allowed search failure count before reporting nominal search failure.

flags

GXF_PARAMETER_FLAGS_DYNAMIC

type

GXF_PARAMETER_TYPE_INT32

default

5

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