Hello,
Many thanks for the amazing library and all your efforts.
I realise that as my observation is in 3.8 it will be low priority etc. but hopefully this helps someone else who may run into the same issue I did after following the documentation and spending sometime confused.
The 3.8 docs specify that the correct syntax for remapping a port ought to be <SubTree ID="MoveRobot" target="{move_goal}"/> however this fails (details on the error message in XML example below) and the correct syntax ought to be <SubTree ID="MoveRobot" target="move_goal"/>.
I came across the fix reading here and here. However, this is contradicted in many other places (eg.).
My own test example is below, including the errors seen and some notes, but the easiest test for checking within this repo is likely here.
I think the solution would simply be a change to the 3.8 documentation on the specific syntax for subtree port remapping.
<?xml version="1.0"?>
<root BTCPP_format="4" >
<BehaviorTree ID="MoveBase">
<Fallback name="move_base_fallback">
<CheckPose name="base_check_location" child_frame="base_link" pose="{base_loc}"/>
<BaseToGoal name="base_to_location" pose="{base_loc}"/>
</Fallback>
</BehaviorTree>
<BehaviorTree ID="HomeBaseModularFailing">
<Sequence name="home_base_modular">
<SetBlackboard output_key="base_home_loc" value="map;-0.5468;-1.4370;0;0;0;0.1942;0.9809"/>
<SubTree ID="MoveBase" base_loc="{base_home_loc}"/>
</Sequence>
</BehaviorTree>
<BehaviorTree ID="HomeBaseModularPassing">
<Sequence name="home_base_modular">
<SetBlackboard output_key="base_home_loc" value="map;-0.5468;-1.4370;0;0;0;0.1942;0.9809"/>
<SubTree ID="MoveBase" base_loc="base_home_loc"/>
</Sequence>
</BehaviorTree>
<BehaviorTree ID="HomeBaseSingularPassing">
<Sequence name="home_base_singular">
<SetBlackboard output_key="base_home_loc" value="map;-0.5468;-1.4370;0;0;0;0.1942;0.9809"/>
<Fallback name="move_base_fallback">
<CheckPose name="base_check_location" child_frame="base_link" pose="{base_home_loc}"/>
<BaseToGoal name="base_to_location" pose="{base_home_loc}"/>
</Fallback>
</Sequence>
</BehaviorTree>
<BehaviorTree ID="MainTree">
<Sequence name="test">
<!--<SubTree ID="HomeBaseModularFailing" />-->
<!--
Error Message:
terminate called after throwing an instance of 'BT::RuntimeError'
what(): CheckPose | error reading port [pose]:getInput() failed because the port [pose] remapped to BB [base_loc] was found,but its content was not initialized correctly
-->
<!--<SubTree ID="HomeBaseSingularPassing" />-->
<SubTree ID="HomeBaseModularPassing" />
<!-- Fix found here:
https://github.com/BehaviorTree/BehaviorTree.CPP/blob/v3.8/examples/t06_subtree_port_remapping.cpp
...and here:
https://github.com/BehaviorTree/BehaviorTree.CPP/issues/173
...but is contradicted in many other places:
https://github.com/BehaviorTree/BehaviorTree.CPP/issues/44
https://www.behaviortree.dev/docs/3.8/tutorial-basics/tutorial_06_subtree_ports/
...also, 'tree.subtrees' does not compile as subtrees is not a valid entity of tree.
-->
</Sequence>
</BehaviorTree>
</root>
Hello, Many thanks for the amazing library and all your efforts.
I realise that as my observation is in 3.8 it will be low priority etc. but hopefully this helps someone else who may run into the same issue I did after following the documentation and spending sometime confused.
The 3.8 docs specify that the correct syntax for remapping a port ought to be
<SubTree ID="MoveRobot" target="{move_goal}"/>
however this fails (details on the error message in XML example below) and the correct syntax ought to be<SubTree ID="MoveRobot" target="move_goal"/>
.I came across the fix reading here and here. However, this is contradicted in many other places (eg.).
My own test example is below, including the errors seen and some notes, but the easiest test for checking within this repo is likely here.
I think the solution would simply be a change to the 3.8 documentation on the specific syntax for subtree port remapping.