Behavior Executor

The behavior executor is responsible for coordination of on-robot behaviors.

It receives and processes mission actions from the on-robot mission client. It then uses a behavior tree to manage downstream modules like path planner to realize specific behaviors needed to accomplish missions. It also monitors important health signals such as, the localization health, and feedback from planners to decide the robot’s mode of operation.

Inputs

  • PoseTree: This library provides the pose frame transform queries.

  • Action: The relevant actions from the currently being executed mission from mission control.

  • Localization Result: The assessment of localization quality as either good or bad.

  • Path Planner Health: The status of path planner’s last cycle as success or failure, plus contextual information.

  • Trajectory Solver Status: The status of trajectory planner solver, indicating relevant failures if any.

  • Semantic regions: Relevant semantic regions, i.e. navigable surfaces and regions of interest, for passing down to the planners.

It also loads up a behavior tree from file, using nodes implemented in the manager component described hereinafter.

Outputs

  • Planner Operation Mode: The selected mode for path planner to operation on, including whether to idle.

  • Route Request: When necessary a request for the onboard route planner to generate a new route.

  • Maneuver: The local planning task, sent to regional path planner and the speed decision maker.

  • Action Feedback: Collected feedback detailing the status of execution of the action received from mission client.

  • Localization Reset Signal: Signal to reset localization when needed, e.g. when map changes

  • Route Planner Reset Signal: Signal to reset onboard route planner when needed, e.g. when map changes

  • Map Republish Signal: Signal to request publishing of maps after loading of new tiles.

  • Entity Enablers/Disablers: Set of enabler/disablers for certain modules (RPP, TP, SDM, etc)

The module is implemented using a collection of Graph eXecution Format (GXF) components, each in charge of key decision making aspect. These include:

Planner Manager

Responsible for consuming and processing feedback from path and trajectory planners, and deciding which operation mode to run next. It uses the planner health and trajectory solver status as inputs and generate planner operation mode as output.

Action Manager

Receives and processes actions from the mission client. It also checks for changes in the goal pose transform to update the target goal if necessary. Internally it decides when the robot has reached the goal, and requests for new routes when needed.

System Health Manager

Receives health signals and determines if the robot can navigate or not. For example, when the localization result indicates bad localization, the robot is set to idle. Also resets localization when needed.

Entity Enabler

Defined behavior tree nodes that allows GXF codelets to be enabled or disabled. When disabled, codelet ticking is stopped, and on resumption of ticking, the start method is called before continuing with ticking.

Autonomy Level Manager

Handles switching between autonomy levels, i.e. manual, teleoperation and autonomous. Useful for integration with remote controllers, and a deadman switch mechanism.

Maneuver Generator

Uses the route waypoints to construct a polyline, thereby building a Frenet coordinate frame. It then uses the robot’s position and regional planning horizon to slice a portion of the route polyline. It then constructs a maneuver using the waypoints in this slice and optionally, semantic objects. This maneuver repesents the next task for the regional planners. The goal is taken at the projection of the robot’s horizon onto the polyline.

Map Manager

Responsible to coordinating map (tile) loading and map changes. When a new request to load a map is received, it disables map-dependent codelets, asks Map Loader to load the new map, resets localization, and then finally enabled the codelets again. The flow of data is shown below

sequenceDiagram Behavior Executor->>+Map Loader: LoadTileRequest Map Loader-->>-Behavior Executor: LoadTileResult Behavior Executor->>+Localization: Reset Signal Localization-->>-Behavior Executor: Localization Result

The coordination of behavior is realized using a behavior tree, loaded from XML files at startup. This behavior tree is implemented using the popular behaviortreecpp library. The files are split to represent functional subtrees. For example, the subtree to check and make sure there is a route before running path and trajectory planners is shown below.

Copy
Copied!
            

<root BTCPP_format="4"> <BehaviorTree ID="SUBTREE_pre_planning_checks"> <Sequence> <!-- Localization must be ready and good --> <Condition ID="localizationIsReady" name="CONDITION_localization_is_good?"/> <Fallback name="FALLBACK_check_route_or_request_one"> <!-- Either a route is already available --> <Condition ID="newRouteAvailable" name="CONDITION_route_available?"/> <!-- Else, request one --> <Action ID="requestNewRouteOnBoard" name="ACTION_request_new_route"/> </Fallback> </Sequence> </BehaviorTree> </root>

The nodes used in the trees are implemented in the components described above. The tree is loaded and ticked from the main behavior executor codelet. As a convention we prepend node type information in the node names, e.g. ACTION_doSomething to make it easy to read the tree when rendered on the terminal.

All the components above are put together in the behavior executor codelet. This codelet takes as inputs, the above components and a filename for the behavior tree to load. For example,

Copy
Copied!
            

# Setup components, input and output channels #... - name: behavior_executor type: nvidia::isaac::BehaviorExecutor parameters: managers: - system_health_manager - planner_manager - action_manager - classical_egm_enabler - map_manager - rpp_enabler - sdm_enabler #- MODULE_X_enabler feedback_collector: feedback_collector behavior_tree_file: "{PATH_TO_TREE_FILES}/navigation_classic.xml" save_tree_nodes: false # Save tree models for use with Groot2 behavior tree visualization tool use_tile_loader: false # Load map tiles dynamically on demand execution_time: execution_metrics/execution_time - type: nvidia::gxf::PeriodicSchedulingTerm parameters: recess_period: 2hz # ... # Additional component like metrics

API Documentation

NvIsaacBehaviorExecutorExtension

Extension containing behavior execution module.

nvidia::isaac::behavior_execution::Maneuver

Holds a maneuver send from behavior executor to path planner.

Parameters:

nvidia::isaac::MessageCache

A component that handles localization result 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::BehaviorManager

A generic behavior manager.

Parameters:

nvidia::isaac::SystemHealthManager

A behavior tree component that checks localization status.

Parameters:

name

Localization result input

lookup_name

localization_result

description

The channel for receiving the localization result.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Outgoing localization reset signal

lookup_name

tx_reset_localization

description

The channel for sending reset signal to localization.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

PoseTree

lookup_name

pose_tree

description

Link to the pose tree.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Robot Frame

lookup_name

robot_frame

description

Pose frame for the robot.

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

Localization Failure Count

lookup_name

localization_failures

description

Metric component to counts the number of times localization failed.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::MessageCache

A component that handles the route 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 action 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 load tile requests.

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 load tile results.

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::ActionManager

A behavior tree component that manages the processing of actions from mission client.

Parameters:

name

Incoming Action

lookup_name

action

description

The channel for receiving action messages from the mission client.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Incoming Semantic Regions

lookup_name

semantic_regions

description

The input channel for the semantic regions from the semantic region extractor.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Outgoing route request

lookup_name

tx_route_request

description

The channel for sending route request to onboard route planner.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Outgoing Route Planner Reset

lookup_name

tx_reset_route_planner

description

The channel for sending signal to reset route planner.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Outgoing Maneuver

lookup_name

tx_maneuver

description

The channel for sending out maneuver message.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Tile load request

lookup_name

tx_tile_load_request

description

The channel for sending out tile load request to map manager.

flags

GXF_PARAMETER_FLAGS_OPTIONAL

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

PoseTree

lookup_name

pose_tree

description

Link to the pose tree.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Robot Frame

lookup_name

robot_frame

description

Pose frame for the robot.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Goal Frame

lookup_name

goal_frame

description

The frame for which the Goal is referenced.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

OMap Frame

lookup_name

omap_frame

description

The name of the map (reference frame for the occupancy grid map) in the pose tree.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Goal Translation Threshold

lookup_name

goal_translation_threshold

description

The translation threshold to determine if we have arrived at goal.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Maneuver Front Horizon

lookup_name

maneuver_front_horizon

description

How far in front to consider when generating maneuvers, along the route.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Maneuver Rear Horizon

lookup_name

maneuver_rear_horizon

description

How far in the rear to consider when generating maneuvers, along the route.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

name

Route Wait Threshold

lookup_name

route_wait_threshold

description

Number of seconds to wait before declaring route not available.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

20.0

name

Actions Executed

lookup_name

actions_executed

description

Metric component to counts the number of mission actions received and executed.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Actions Completed

lookup_name

actions_completed

description

Metric component to counts the number of mission actions that were completed.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::MessageCache

A component that handles path planner health 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::PlannerManager

A behavior tree component that manages the path planner.

Parameters:

name

Path Planner Health input

lookup_name

path_planner_health

description

The channel for receiving planner feedback message.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Trajectory

lookup_name

trajectory

description

The trajectory sent from TP to control to track/follow. Has LQR status needed here.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Output RPP operation mode

lookup_name

tx_planner_operation_mode

description

The channel for publishing RPP operation mode.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Total Path Planning Cycles

lookup_name

total_path_planning_cycles

description

Metric component to counts the number of path planning cycles.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Nominal Path Planning Cycles

lookup_name

path_planning_nominal_cycles

description

Metric component to counts the number of path planning cycles in nominal mode

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Fallback Path Planning Cycles

lookup_name

path_planning_fallback_cycles

description

Metric component to counts the number of path planning cycles in fallback mode.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Idle Path Planning Cycles

lookup_name

path_planning_idle_cycles

description

Metric component to counts the number of path planning cycles in idle mode.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Path Planning Cycles with Rerouting

lookup_name

path_planning_reroute_cycles

description

Metric component to counts the number of path planning cycles that requested rerouting.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

TP Constraint Computation Failures

lookup_name

tp_constraint_failed

description

Metric component to counts constraint computation TP failures.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

TP Invalid Trajectory Failures

lookup_name

tp_invalid_trajectory

description

Metric component to counts invalid trajectory TP failures.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

TP Line Search Failures

lookup_name

tp_line_search_failed

description

Metric component to counts line search TP failures.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

TP Unsatisfied Constraints Failures

lookup_name

tp_unsatisfied_constraints

description

Metric component to counts unsatisfied constraints TP failures.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

TP Cost Computation Failures

lookup_name

tp_cost_failed

description

Metric component to counts cost computation TP failures.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

TP Out-of-Memory Failures

lookup_name

tp_out_of_memory

description

Metric component to counts out-of-memory TP failures.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::MapManager

A behavior tree component that manages map loading and usage.

Parameters:

name

Outgoing Load Tile Request

lookup_name

tx_load_tile_request

description

The channel for sending request to Map Loader to load a map tile.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Outgoing Publish Map Signal

lookup_name

tx_atlas_map_publisher

description

The channel for sending a signal containing acquisition time to Atlas map publisher to publish map.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Incoming Load Tile Request

lookup_name

load_tile_request

description

The channel for receiving requests to initiate map tile loading.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Incoming Load Tile Result

lookup_name

load_tile_result

description

The channel for receiving results of map tile loading from Map Loader.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::FeedbackCollector

A component that collects feedback from the navigation stack and publishing to the mission client.

Parameters:

name

Outgoing Action Feedback Message

lookup_name

tx_action_feedback

description

The channel for sending out action feedback message.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::EntityManager

A behavior tree manager that allows to dis-/enable an entity.

Parameters:

name

Enable Signal Channel

lookup_name

tx_enabler

description

The channel used to send the signal to dis/enable the entity.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Managed Entity Name

lookup_name

managed_entity_name

description

This name will be used to generate the behavior tree action nodes to dis/enable the entity. The action nodes will be named ‘<name>Enable’, ‘<name>Disable’ and ‘<name>Toggle’. Thus this name should be written in the camelCase convention.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

nvidia::isaac::AutonomyLevelManager

A component that manages the remote control.

Parameters:

name

Mode Toggle Request Channel

lookup_name

rx_autonomy_mode_toggled

description

When an entity is received on this channel it is interpreted as a request to toggle the operation mode between manual and autonomy mode.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Deadman Switch Heartbeat Input Channel

lookup_name

rx_deadman_switch_heartbeat

description

Message channel used to receive the heartbeat from the deadman switch.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Autonomy Level Output Channel

lookup_name

tx_autonomy_level

description

Message channel used to send the current autonomy level.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Deadman Switch Timeout [s]

lookup_name

deadman_switch_timeout_s

description

Timeout used for the deadman switch. If set to a value <= 0.0, the deadman switch is ignored.

flags

GXF_PARAMETER_FLAGS_DYNAMIC

type

GXF_PARAMETER_TYPE_FLOAT64

default

N/A

nvidia::isaac::LocalActionGenerator

Codelet that translates local routes into actions.

Parameters:

name

Input Route

lookup_name

rx_route

description

Message channel used to receive the route from onboard (local) route planner.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Outgoing Action

lookup_name

tx_action

description

The channel for sending out action message.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::BehaviorExecutor

The executor for the navigation behavior tree.

Parameters:

name

Behavior Managers

lookup_name

managers

description

The list of components that manage specific behavior.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Feedback Collector

lookup_name

feedback_collector

description

The component that collects and publishes navigation feedback to mission client.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Behavior Tree File

lookup_name

behavior_tree_file

description

The full path to the behavior tree file to use.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_STRING

default

N/A

name

Save Tree Nodes

lookup_name

save_tree_nodes

description

Flag to optionally save the BT nodes to file (for later use in Groot2 visualization)

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_BOOL

default

N/A

name

Use Tile Loader

lookup_name

use_tile_loader

description

Flag to indicate is the tile loader portion of the subtree should be loaded.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_BOOL

default

N/A

name

Execution Time Stats

lookup_name

execution_time

description

Metric component to record execution times for each tick.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

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