Passing Parameters to Objectives at Runtime
The parameter_overrides field on DoObjectiveSequence allows an external application to inject values into a Behavior Tree's blackboard at runtime, without editing the Objective XML. Use this when a state machine, fleet manager, or REST caller needs to hand an Objective context such as a target pose, a map identifier, or a joint state.
How It Works
When you send a DoObjectiveSequence goal with parameter_overrides:
- MoveIt Pro builds the Behavior Tree from the Objective definition.
- For each override, it looks up the C++ type declared by the matching port in the tree.
- It runs the registered parser for that type, which parses the
string_valueas YAML into a strongly-typed value. - It writes the typed value to the target blackboard (root by default, or specific Subtrees if
behavior_namespacesis provided). - The tree runs. Behaviors read the override via
getInput<T>(port_name)and get the typed value directly — no per-BehaviorBT::convertFromString<T>specialization is required.
If a parameter cannot be applied (unknown type, YAML parse failure, no matching port), the goal is aborted before the tree runs. Overrides never partially apply.
Built-in Type Support
The following types can be used in parameter_overrides out of the box. Values are expressed as YAML strings.
| Type | Example Value |
|---|---|
std::string | "hello world" |
double, int, bool | "3.14", "42", "true" |
geometry_msgs/PoseStamped | "{header: {frame_id: world}, pose: {position: {x: 1.0, y: 0, z: 0}, orientation: {x: 0, y: 0, z: 0, w: 1}}}" |
geometry_msgs/PointStamped | "{header: {frame_id: world}, point: {x: 1, y: 2, z: 3}}" |
geometry_msgs/TransformStamped | "{header: {frame_id: world}, child_frame_id: base, transform: {translation: {x: 1, y: 0, z: 0}, rotation: {x: 0, y: 0, z: 0, w: 1}}}" |
geometry_msgs/Twist | "{linear: {x: 0.5, y: 0, z: 0}, angular: {x: 0, y: 0, z: 0.1}}" |
geometry_msgs/TwistStamped | "{header: {frame_id: base_link}, twist: {linear: {x: 0.5, y: 0, z: 0}, angular: {x: 0, y: 0, z: 0.1}}}" |
geometry_msgs/Wrench | "{force: {x: 10, y: 0, z: -5}, torque: {x: 0, y: 0, z: 0.5}}" |
geometry_msgs/WrenchStamped | "{header: {frame_id: tool0}, wrench: {force: {x: 10, y: 0, z: -5}, torque: {x: 0, y: 0, z: 0.5}}}" |
sensor_msgs/JointState | "{header: {frame_id: ''}, name: [joint_1, joint_2], position: [0.0, 1.57], velocity: [], effort: []}" |
trajectory_msgs/JointTrajectory | YAML format for joint names, points, and time_from_start. |
YAML::Node | Any valid YAML, for free-form data. |
std::vector<PoseStamped> | YAML sequence of PoseStamped. |
std::vector<PointStamped> | YAML sequence of PointStamped. |
Basic Usage
parameter_overrides is a field on the DoObjectiveSequence action goal (and the ExecuteObjective service request). All YAML decoding happens server-side in the MoveIt Pro agent, so any client that can send a goal or service request to /do_objective or /execute_objective supports overrides — native ROS 2 client libraries (rclpy, rclcpp) and websocket libraries that speak the rosbridge protocol (roslibpy, roslibjs, etc.) all use the same payload shape.
- Python (rclpy)
- Python (roslibpy)
- Command Line
from moveit_studio_sdk_msgs.action import DoObjectiveSequence
from moveit_studio_sdk_msgs.msg import BehaviorParameter
goal = DoObjectiveSequence.Goal()
goal.objective_name = "Navigate To Pose"
# Pass a PoseStamped as a YAML string.
param = BehaviorParameter()
param.description.name = "target_pose"
param.string_value = """{
header: {frame_id: map},
pose: {
position: {x: 1.0, y: 2.0, z: 0.0},
orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0}
}
}"""
goal.parameter_overrides.append(param)
See the Programmatic SDKs overview for roslibpy setup. Once connected, the goal is a plain dict — the field names match the underlying ROS message exactly, so the same YAML string_value works.
import roslibpy
from roslibpy import ActionClient
client = roslibpy.Ros(host='localhost', port=3201)
client.run()
action = ActionClient(
client,
'/do_objective',
'moveit_studio_sdk_msgs/action/DoObjectiveSequence'
)
goal = {
"objective_name": "Navigate To Pose",
"parameter_overrides": [
{
"description": {"name": "target_pose"},
"string_value": (
"{header: {frame_id: map},"
" pose: {position: {x: 1.0, y: 2.0, z: 0.0},"
" orientation: {x: 0, y: 0, z: 0, w: 1}}}"
),
}
],
}
action.send_goal(goal, lambda r: None, lambda f: None, lambda e: None)
The same parameter_overrides list works with the synchronous /execute_objective service via roslibpy.Service — see Using the ExecuteObjective Service.
ros2 action send_goal /do_objective moveit_studio_sdk_msgs/action/DoObjectiveSequence "
objective_name: 'Navigate To Pose'
parameter_overrides:
- description:
name: target_pose
string_value: '{header: {frame_id: map}, pose: {position: {x: 1.0, y: 2.0, z: 0.0}, orientation: {x: 0, y: 0, z: 0, w: 1}}}'
"
Targeting Specific Subtrees
By default, overrides are set on the root blackboard. To target a specific Subtree, use behavior_namespaces:
- Python (rclpy)
- Python (roslibpy)
- Command Line
param = BehaviorParameter()
param.description.name = "target_pose"
param.string_value = "{header: {frame_id: map}, pose: {position: {x: 1, y: 0, z: 0}, orientation: {x: 0, y: 0, z: 0, w: 1}}}"
param.behavior_namespaces = ["Move to Waypoint"]
goal.parameter_overrides.append(param)
goal["parameter_overrides"].append(
{
"description": {"name": "target_pose"},
"string_value": (
"{header: {frame_id: map},"
" pose: {position: {x: 1, y: 0, z: 0},"
" orientation: {x: 0, y: 0, z: 0, w: 1}}}"
),
"behavior_namespaces": ["Move to Waypoint"],
}
)
ros2 action send_goal /do_objective moveit_studio_sdk_msgs/action/DoObjectiveSequence "
objective_name: 'Navigate To Pose'
parameter_overrides:
- description:
name: target_pose
string_value: '{header: {frame_id: map}, pose: {position: {x: 1, y: 0, z: 0}, orientation: {x: 0, y: 0, z: 0, w: 1}}}'
behavior_namespaces: [Move to Waypoint]
"
The value is set on every Subtree whose instance_name (or tree_ID, if instance_name is empty) matches one of the listed namespaces. Namespaces that do not match any Subtree are silently skipped with a warning in the agent logs.
Supporting Custom Message Types
For message types not listed above (typically messages defined in your own package), you need two things:
- A
YAML::convert<T>specialization so yaml-cpp can decode YAML into your message. - A registration call so MoveIt Pro knows the parser exists.
Both are provided by helpers that already ship with MoveIt Pro — you do not have to write boilerplate per-type.
Step 1: Define Your Message
# your_msgs/msg/MapMetadata.msg
string map_id
float64 resolution
geometry_msgs/PoseStamped origin
string[] layer_names
Step 2: Add the YAML Converter
In any header in your Behavior package, invoke ROS_MESSAGE_YAML_PARSER from moveit_pro_common/utils/yaml_parsing_tools.hpp. This expands to a YAML::convert<T> specialization driven by the dynmsg reflection library, so field-by-field decoding is automatic.
// your_behaviors/include/your_behaviors/map_metadata_yaml.hpp
#pragma once
#include <moveit_pro_common/utils/yaml_parsing_tools.hpp>
#include <your_msgs/msg/map_metadata.hpp>
ROS_MESSAGE_YAML_PARSER(your_msgs, MapMetadata)
Step 3: Register the Type With the Override Registry
Inside your Behavior loader plugin's registerBehaviors(), call registerParameterType<T>() once per custom type. This registers both the parameter override parser and the Blackboard Panel JSON converter, so the value is also rendered as structured JSON in the UI.
// your_behaviors/src/register_behaviors.cpp
#include <moveit_pro_behavior_interface/parameter_override_registry.hpp>
#include "your_behaviors/map_metadata_yaml.hpp"
void YourBehaviorsLoader::registerBehaviors(
BT::BehaviorTreeFactory& factory,
const std::shared_ptr<moveit_pro::behaviors::BehaviorContext>& shared_resources)
{
// ... register your behaviors ...
moveit_pro::behavior::registerParameterType<your_msgs::msg::MapMetadata>();
}
That's it. With the YAML converter and the registry entry in place, your Behavior's getInput<your_msgs::msg::MapMetadata>("map_metadata") will receive a typed value when an override targets that port.
Step 4: Send the Override
Once the custom type is registered server-side, any client can send YAML for it — no client-side schema is required, since YAML decoding still happens in the agent.
- Python (rclpy)
- Python (roslibpy)
- Command Line
param = BehaviorParameter()
param.description.name = "map_metadata"
param.string_value = """
map_id: warehouse_floor
resolution: 0.05
origin:
header:
frame_id: map
pose:
position: {x: 1.0, y: 2.0, z: 0.0}
orientation: {x: 0, y: 0, z: 0, w: 1}
layer_names: [obstacles, inflation, costmap]
"""
goal.parameter_overrides.append(param)
goal["parameter_overrides"].append(
{
"description": {"name": "map_metadata"},
"string_value": (
"map_id: warehouse_floor\n"
"resolution: 0.05\n"
"origin:\n"
" header: {frame_id: map}\n"
" pose:\n"
" position: {x: 1.0, y: 2.0, z: 0.0}\n"
" orientation: {x: 0, y: 0, z: 0, w: 1}\n"
"layer_names: [obstacles, inflation, costmap]\n"
),
}
)
ros2 action send_goal /do_objective moveit_studio_sdk_msgs/action/DoObjectiveSequence "
objective_name: 'Build Map'
parameter_overrides:
- description:
name: map_metadata
string_value: |
map_id: warehouse_floor
resolution: 0.05
origin:
header: {frame_id: map}
pose:
position: {x: 1.0, y: 2.0, z: 0.0}
orientation: {x: 0, y: 0, z: 0, w: 1}
layer_names: [obstacles, inflation, costmap]
"
Step 5: Test the Conversion
#include <gtest/gtest.h>
#include <behaviortree_cpp/blackboard.h>
#include <moveit_pro_behavior_interface/parameter_override_registry.hpp>
#include "your_behaviors/map_metadata_yaml.hpp"
TEST(MapMetadataConversions, ConvertFromYaml)
{
moveit_pro::behavior::registerParameterType<your_msgs::msg::MapMetadata>();
const auto* parser = moveit_pro::behavior::ParameterOverrideRegistry::get().findParser(
std::type_index(typeid(your_msgs::msg::MapMetadata)));
ASSERT_NE(parser, nullptr);
auto blackboard = BT::Blackboard::create();
const auto result = (*parser)(*blackboard, "map_metadata", R"(
map_id: warehouse_floor
resolution: 0.05
origin:
header: {frame_id: map}
pose:
position: {x: 1.0, y: 2.0, z: 0.0}
orientation: {x: 0, y: 0, z: 0, w: 1}
layer_names: [obstacles, inflation, costmap]
)");
ASSERT_TRUE(result.has_value()) << result.error();
const auto map = blackboard->get<your_msgs::msg::MapMetadata>("map_metadata");
EXPECT_EQ(map.map_id, "warehouse_floor");
EXPECT_DOUBLE_EQ(map.resolution, 0.05);
ASSERT_EQ(map.layer_names.size(), 3u);
}
Troubleshooting
Parameter override 'X' does not match any typed port on subtree 'Y'
The override key does not correspond to any blackboard remapping ({X}) on a typed port in the named Subtree.
- Verify the port name in the override matches the blackboard remapping exactly. The key in the override is the part inside the curly braces in the Objective XML, not the port name on the Behavior.
- Confirm that the port is wired with the
{}syntax in the Objective XML (e.g.,target_pose="{target_pose}"). A literal value on a port has no blackboard entry to override.
Parameter override 'X' has port type 'T' but no parser is registered
The override targets a port whose C++ type has no parser. MoveIt Pro will not silently fall back to string storage.
- For a built-in type, ensure it appears in the table above. If not, file an issue.
- For a custom type, call
moveit_pro::behavior::registerParameterType<T>()in your Behavior loader plugin'sregisterBehaviors(). The error message includes the demangled type name.
Parameter override 'X': YAML parse failed: ...
string_value is not valid YAML for the destination type. Validate the YAML out-of-band — python -c "import yaml; yaml.safe_load(open('payload.yaml'))" is a quick check — and verify field names match the message definition.
Cannot apply parameter overrides: tree not initialized
applyParameterOverrides was called before createTree. Only the agent calls these in order, so seeing this message indicates a bug — please report it.