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
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.
<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,
# 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
- 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::BehaviorManager
A generic behavior manager.
Parameters:
nvidia::isaac::SystemHealthManager
A behavior tree component that checks localization status.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Localization result input
localization_result
The channel for receiving the localization result.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Outgoing localization reset signal
tx_reset_localization
The channel for sending reset signal to localization.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
PoseTree
pose_tree
Link to the pose tree.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Robot Frame
robot_frame
Pose frame for the robot.
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
Localization Failure Count
localization_failures
Metric component to counts the number of times localization failed.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::MessageCache
A component that handles the route 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 action 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 load tile requests.
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 load tile results.
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::ActionManager
A behavior tree component that manages the processing of actions from mission client.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Incoming Action
action
The channel for receiving action messages from the mission client.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming Semantic Regions
semantic_regions
The input channel for the semantic regions from the semantic region extractor.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Outgoing route request
tx_route_request
The channel for sending route request to onboard route planner.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Outgoing Route Planner Reset
tx_reset_route_planner
The channel for sending signal to reset route planner.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Outgoing Maneuver
tx_maneuver
The channel for sending out maneuver message.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Tile load request
tx_tile_load_request
The channel for sending out tile load request to map manager.
GXF_PARAMETER_FLAGS_OPTIONAL
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
PoseTree
pose_tree
Link to the pose tree.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Robot Frame
robot_frame
Pose frame for the robot.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Goal Frame
goal_frame
The frame for which the Goal is referenced.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
OMap Frame
omap_frame
The name of the map (reference frame for the occupancy grid map) in the pose tree.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Goal Translation Threshold
goal_translation_threshold
The translation threshold to determine if we have arrived at goal.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Maneuver Front Horizon
maneuver_front_horizon
How far in front to consider when generating maneuvers, along the route.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Maneuver Rear Horizon
maneuver_rear_horizon
How far in the rear to consider when generating maneuvers, along the route.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
N/A
- name
- lookup_name
- description
- flags
- type
- default
Route Wait Threshold
route_wait_threshold
Number of seconds to wait before declaring route not available.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
20.0
- name
- lookup_name
- description
- flags
- type
- default
Actions Executed
actions_executed
Metric component to counts the number of mission actions received and executed.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Actions Completed
actions_completed
Metric component to counts the number of mission actions that were completed.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::MessageCache
A component that handles path planner health 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::PlannerManager
A behavior tree component that manages the path planner.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Path Planner Health input
path_planner_health
The channel for receiving planner feedback message.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Trajectory
trajectory
The trajectory sent from TP to control to track/follow. Has LQR status needed here.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Output RPP operation mode
tx_planner_operation_mode
The channel for publishing RPP operation mode.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Total Path Planning Cycles
total_path_planning_cycles
Metric component to counts the number of path planning cycles.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Nominal Path Planning Cycles
path_planning_nominal_cycles
Metric component to counts the number of path planning cycles in nominal mode
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Fallback Path Planning Cycles
path_planning_fallback_cycles
Metric component to counts the number of path planning cycles in fallback mode.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Idle Path Planning Cycles
path_planning_idle_cycles
Metric component to counts the number of path planning cycles in idle mode.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Path Planning Cycles with Rerouting
path_planning_reroute_cycles
Metric component to counts the number of path planning cycles that requested rerouting.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
TP Constraint Computation Failures
tp_constraint_failed
Metric component to counts constraint computation TP failures.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
TP Invalid Trajectory Failures
tp_invalid_trajectory
Metric component to counts invalid trajectory TP failures.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
TP Line Search Failures
tp_line_search_failed
Metric component to counts line search TP failures.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
TP Unsatisfied Constraints Failures
tp_unsatisfied_constraints
Metric component to counts unsatisfied constraints TP failures.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
TP Cost Computation Failures
tp_cost_failed
Metric component to counts cost computation TP failures.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
TP Out-of-Memory Failures
tp_out_of_memory
Metric component to counts out-of-memory TP failures.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::MapManager
A behavior tree component that manages map loading and usage.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Outgoing Load Tile Request
tx_load_tile_request
The channel for sending request to Map Loader to load a map tile.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Outgoing Publish Map Signal
tx_atlas_map_publisher
The channel for sending a signal containing acquisition time to Atlas map publisher to publish map.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming Load Tile Request
load_tile_request
The channel for receiving requests to initiate map tile loading.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Incoming Load Tile Result
load_tile_result
The channel for receiving results of map tile loading from Map Loader.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::FeedbackCollector
A component that collects feedback from the navigation stack and publishing to the mission client.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Outgoing Action Feedback Message
tx_action_feedback
The channel for sending out action feedback message.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::EntityManager
A behavior tree manager that allows to dis-/enable an entity.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Enable Signal Channel
tx_enabler
The channel used to send the signal to dis/enable the entity.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Managed Entity Name
managed_entity_name
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.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
nvidia::isaac::AutonomyLevelManager
A component that manages the remote control.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Mode Toggle Request Channel
rx_autonomy_mode_toggled
When an entity is received on this channel it is interpreted as a request to toggle the operation mode between manual and autonomy mode.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Deadman Switch Heartbeat Input Channel
rx_deadman_switch_heartbeat
Message channel used to receive the heartbeat from the deadman switch.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Autonomy Level Output Channel
tx_autonomy_level
Message channel used to send the current autonomy level.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Deadman Switch Timeout [s]
deadman_switch_timeout_s
Timeout used for the deadman switch. If set to a value <= 0.0, the deadman switch is ignored.
GXF_PARAMETER_FLAGS_DYNAMIC
GXF_PARAMETER_TYPE_FLOAT64
N/A
nvidia::isaac::LocalActionGenerator
Codelet that translates local routes into actions.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Input Route
rx_route
Message channel used to receive the route from onboard (local) route planner.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Outgoing Action
tx_action
The channel for sending out action message.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::BehaviorExecutor
The executor for the navigation behavior tree.
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Behavior Managers
managers
The list of components that manage specific behavior.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Feedback Collector
feedback_collector
The component that collects and publishes navigation feedback to mission client.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Behavior Tree File
behavior_tree_file
The full path to the behavior tree file to use.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_STRING
N/A
- name
- lookup_name
- description
- flags
- type
- default
Save Tree Nodes
save_tree_nodes
Flag to optionally save the BT nodes to file (for later use in Groot2 visualization)
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_BOOL
N/A
- name
- lookup_name
- description
- flags
- type
- default
Use Tile Loader
use_tile_loader
Flag to indicate is the tile loader portion of the subtree should be loaded.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_BOOL
N/A
- name
- lookup_name
- description
- flags
- type
- default
Execution Time Stats
execution_time
Metric component to record execution times for each tick.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A