Skip to main content
Version: 6

Behaviors

In MoveIt Pro, Behaviors are the building blocks used to create Objectives. They define a discrete sensing, planning, motion execution, or decision-making step.

MoveIt Pro includes a collection of predefined Behavior plugins which enable fundamental planning, execution, and perception capabilities.

For more information on available Behavior interfaces, refer to the Technical Documentation for the MoveIt Pro Behavior Interface

List of Core Behaviors

Documentation for built-in Behaviors is provided in the MoveIt Pro Behavior Package.

Additional Details

Parameterizing Behaviors using Configuration Parameters

Some Behaviors can be parameterized using a separate configuration file that effectively extends the objective definition file.

Note that using configuration files is optional. If the Objective does not require parameters, a configuration file does not have to be created or loaded.

Loading Configuration Parameters

To load parameters for an Objective and to pass them to Behaviors within the Objective, you can add LoadObjectiveParameters Behaviors to your Objective.

You must specify the configuration file name as an input port to each LoadObjectiveParameters Behavior, which then searches for the configuration file from the Objective library directories.

The loader verifies that the configuration YAML files exist and that they are valid YAML files that can be parsed. The parameters are made available for all the parameterized Behaviors by writing them to a Behavior tree output port. All the parameterized Behaviors can access the parameter set by reading them from a matching Behavior tree input port.

Defining a parameter input port is not required for Behaviors that do not use the parameters.

The parameters are matched with the Behaviors based on each Behavior's name. If the Objective contains multiple instances of the same Behavior, and they all have the same name, then the parameters defined for one of the Behaviors apply to all of them.

To differentiate between Behavior instances of the same type, unique names should be assigned to all the Behaviors. For instance, a configuration file such as this:

PerceptionBehavior:
min_detection_confidence: 0.95
PlanningBehavior:
max_planning_time: 5.0
OtherPlanningBehavior:
max_planning_time: 10.0

would assign min_detection_confidence of 0.95 to all the instances of PerceptionBehavior, max_planning_time of 5.0 to an instance of a planning Behavior with a name of PlanningBehavior and 10.0 for the same parameter to an instance of planning Behavior with a name of OtherPlanningBehavior.

The objective definition XML file that uses this configuration file could look like this:

<?xml version="1.0"?>
<root BTCPP_format="4" main_tree_to_execute="My Objective">
<BehaviorTree ID="My Objective">
<Sequence name="main">
<Action ID="LoadObjectiveParameters" config_file_name="my_objective_config_file.yaml" parameters="{parameters}"/>
<Action ID="PerceptionBehavior" parameters="{parameters}"/>
<Action ID="PlanningBehavior" parameters="{parameters}"/>
<Action ID="PlanningBehavior" name="OtherPlanningBehavior" parameters="{parameters}"/>
</Sequence>
</BehaviorTree>
</root>

Objective Parameter Example

There are a few things to consider when working with Objectives that have configuration files:

  • If the configuration file name contains the Objective file name, actions such as cloning or renaming the objective will ensure the configuration file is renamed according to the Objective file name.
  • Otherwise, configuration files are treated as standalone files that can be used across multiple Objectives.
  • If an Objective is deleted, and it is the only one using a set of configuration files, those files may be deleted. You can avoid this by tagging the file as persistent:
persistent: True
PerceptionBehavior:
min_detection_confidence: 0.95
PlanningBehavior:
max_planning_time: 5.0
OtherPlanningBehavior:
max_planning_time: 10.0

Tweaking Configuration Parameters

If an objective parameter loader Behavior is part of the objective definition, the configuration file is loaded and parsed every time the Behavior gets ticked, which is typically once per objective execution.

Since the configuration file is reloaded every time the objective is executed, it is possible to change the parameter values between executions without restarting any of the software components.

To tweak the configuration parameters, run the objective, change any of the parameters you want and just rerun the objective.

When to Use Input Ports and Parameters

Behaviors should be written similar to functions, that is, they should have single responsibility and, ideally, no side effects. Data can be passed between Behaviors using input and output ports. The ports should be used for runtime generated data that isn't known ahead of time.

Within an objective definition, it is possible to use input ports with hardcoded values to pass in "static" parameters that are known ahead of time, but it is not recommended to do so. It makes for a much cleaner objective definition, especially when the number of parameterized Behaviors is high, if the parameters are placed to a separate configuration file. In addition, more complex data is easier to read and maintain if it is placed into a configuration file. A typical example of a more complex data would be a 6DOF pose.

Note that when using a configuration loader Behavior, the whole set of parameters is passed to different Behaviors via the input/output port mechanism, so it is treated like any other runtime generated data. The one exception to this guideline is the parameter loader Behavior itself, which always must have the configuration file name as an input port to it. Meaning it is defined in the objective definition file.

Motion Planning and Execution via MTC Behaviors

A core feature of the MoveIt Pro SDK is the ability to compose Moveit Task Constructor (MTC) Tasks that define motion plans.

More information on MTC can be found as part of MoveIt2 Tutorials.

Multiple Behaviors work together to create an MTC Task, populate it with a sequence of Stages, and finally plan and execute it. Several minimal requirements must be satisfied:

  • The InitializeMTCTask Behavior must be run first to create a new Task. The key for the output data port should be set to a new value unique to this Task within the scope of the Objective. Each Task should only be configured by a single InitializeMTCTask Behavior.
    • Note: While multiple subsequent Behaviors may modify the Task, the Task will not be planned until it is passed to a PlanMTCTask Behavior. Until that point, it only represents a "recipe" for a motion planning scenario.
  • The SetupMTCCurrentState Behavior must be run next to add a connection between the current state of the robot and the planned motion.
    • Note: Subsequent work may add different Behaviors that can be used instead of SetupMTCCurrentState to allow multiple Tasks to be planned concurrently.
  • After that, additional SetupMTC Behaviors may be added to the Task to add additional motion planning MTC Stages.
  • Once the Task has been configured as desired, add a PlanMTCTask Behavior that takes this Task as an input port. Set the key of the output data port for the solution to a new value unique for this Task. This Behavior will attempt to solve the MTC Task and produce a solution if one exists.
  • Finally, add an ExecuteMTCTask Behavior that takes the solution as an input port. When this Behavior is executed, it will use MoveIt's motion execution interface to perform the planned robot trajectory.

When the Behavior tree for the Objective is executed, each of these Behaviors will individually succeed or fail. The Behavior tree can be designed to perform a fallback action if any individual Behavior fails.

Here is a practical example of an Objective XML definition that plans and executes a freespace motion from the robot's current state to a joint state associated with a named waypoint:

<?xml version="1.0"?>
<root BTCPP_format="4" main_tree_to_execute="Move to Known Pose">
<BehaviorTree ID="Move to Known Pose">
<Sequence>
<Action ID="RetrieveWaypoint" waypoint_name="home" waypoint_joint_state="{target_joint_state}" joint_group_name="manipulator"/>

<!-- Initialize, setup, plan, and execute the MTC task -->
<Action ID="InitializeMTCTask" task_id="move_to_waypoint" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" task="{move_to_waypoint_task}"/>
<Action ID="SetupMTCCurrentState" task="{move_to_waypoint_task}"/>
<Action ID="SetupMTCMoveToJointState" joint_state="{target_joint_state}" name="SetupMTCMoveToJointState_First" planning_group_name="manipulator" task="{move_to_waypoint_task}"/>
<Action ID="PlanMTCTask" task="{move_to_waypoint_task}" solution="{move_to_waypoint_solution}" />
<Action ID="ExecuteMTCTask" solution="{move_to_waypoint_solution}"/>
</Sequence>
</BehaviorTree>
</root>