Run an Objective from a Custom Behavior Tree XML
DoObjectiveSequence accepts two mutually-relevant fields on its goal:
objective_name— the name of an Objective saved in your robot configuration.objective_xml_string— a complete Behavior Tree XML string to execute.
If both are populated, objective_name takes precedence. Use objective_xml_string when you want to run an ad-hoc tree, wrap an existing Subtree with different port values, or compose a tree programmatically. For the basic "run a saved Objective" flow, see Run an Existing Objective.
Wrap an Existing Subtree With Custom Port Values
This pattern is the most common reason to send XML: you have a Subtree saved in the UI (for example Move to Waypoint) and you want to call it from code with different port values without authoring a new Objective for every combination.
The example below assumes the lab_sim config and sets waypoint_name="Look at Table". Change waypoint_name to another valid waypoint (for example Park Far Right) to retarget the motion.
The roslibpy tab connects over the legacy rosbridge protocol, which is off by default. Start the sidecar with moveit_pro run -c <your_config> --enable-rosbridge (default port 3204); see Legacy Websocket Compatibility. Native rclpy is the recommended path.
- Python (rclpy)
- Python (roslibpy)
- Command Line
import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
from moveit_studio_sdk_msgs.action import DoObjectiveSequence
OBJECTIVE_XML = """
<root BTCPP_format="4" main_tree_to_execute="Move to Waypoint Remapped">
<BehaviorTree ID="Move to Waypoint Remapped">
<Control ID="Sequence" name="TopLevelSequence">
<SubTree
ID="Move to Waypoint"
_collapsed="true"
waypoint_name="Look at Table"
joint_group_name="manipulator"
controller_names="joint_trajectory_controller"
use_all_planners="false"
/>
</Control>
</BehaviorTree>
</root>
"""
rclpy.init()
node = Node("custom_xml_client")
action_client = ActionClient(node, DoObjectiveSequence, "/do_objective")
action_client.wait_for_server(timeout_sec=5.0)
goal_msg = DoObjectiveSequence.Goal(objective_xml_string=OBJECTIVE_XML)
send_goal_future = action_client.send_goal_async(goal_msg)
rclpy.spin_until_future_complete(node, send_goal_future)
goal_handle = send_goal_future.result()
result_future = goal_handle.get_result_async()
rclpy.spin_until_future_complete(node, result_future)
result = result_future.result().result
print(f"Error code: {result.error_code.val}")
node.destroy_node()
rclpy.shutdown()
Requires the opt-in rosbridge sidecar (see the note above). Replace 3204 if you passed --rosbridge-port.
import time
import roslibpy
from roslibpy import ActionClient
OBJECTIVE_XML = """
<root BTCPP_format="4" main_tree_to_execute="Move to Waypoint Remapped">
<BehaviorTree ID="Move to Waypoint Remapped">
<Control ID="Sequence" name="TopLevelSequence">
<SubTree
ID="Move to Waypoint"
_collapsed="true"
waypoint_name="Look at Table"
joint_group_name="manipulator"
controller_names="joint_trajectory_controller"
use_all_planners="false"
/>
</Control>
</BehaviorTree>
</root>
"""
client = roslibpy.Ros(host="localhost", port=3204)
client.run()
action = ActionClient(
client,
"/do_objective",
"moveit_studio_sdk_msgs/action/DoObjectiveSequence",
)
done = False
def on_result(result):
global done
values = result.get("values", {})
error_code = values.get("error_code", {})
print(f"Error code: {error_code.get('val', 'unknown')}")
print(f"Error message: {values.get('error_message', 'none')}")
done = True
def on_feedback(feedback):
print(f"Feedback: {feedback}")
def on_error(error):
global done
print(f"Action failed: {error}")
done = True
action.send_goal({"objective_xml_string": OBJECTIVE_XML}, on_result, on_feedback, on_error)
start = time.time()
while not done and (time.time() - start) < 60:
time.sleep(0.1)
client.terminate()
ros2 action send_goal /do_objective moveit_studio_sdk_msgs/action/DoObjectiveSequence '
objective_xml_string: |
<root BTCPP_format="4" main_tree_to_execute="Move to Waypoint Remapped">
<BehaviorTree ID="Move to Waypoint Remapped">
<Control ID="Sequence" name="TopLevelSequence">
<SubTree
ID="Move to Waypoint"
_collapsed="true"
waypoint_name="Look at Table"
joint_group_name="manipulator"
controller_names="joint_trajectory_controller"
use_all_planners="false"
/>
</Control>
</BehaviorTree>
</root>
'
Send a Minimal Ad-Hoc Objective
For quick verification — for example confirming the action interface is reachable — send a trivial tree:
ros2 action send_goal /do_objective moveit_studio_sdk_msgs/action/DoObjectiveSequence '
objective_xml_string: |
<root BTCPP_format="4" main_tree_to_execute="test_simple">
<BehaviorTree ID="test_simple">
<Control ID="Sequence" name="TopLevelSequence">
<Action ID="AlwaysSuccess"/>
</Control>
</BehaviorTree>
</root>
'
The Objective will appear momentarily in the UI and complete with SUCCESS.
When to Use Port Remapping vs. Parameter Overrides
Two mechanisms can inject runtime values into a Behavior Tree:
- Port remapping in XML (this page) — substitute string-typed port values inside the XML you send. Best when the values are literals you already know at client compile-time and you want to express them with the same XML syntax used in the Studio editor.
parameter_overrides— leave the XML alone and inject strongly-typed values via theparameter_overridesfield on the goal. Best when the values come from outside the client (sensor data, a fleet manager, structured ROS messages such asPoseStamped).
See Passing Parameters to Objectives at Runtime for the parameter-overrides path.