Closed
Description
According to the documentation https://www.behaviortree.dev/docs/guides/pre_post_conditions#example, precondition should behave exactly like the inverted condition, but in practice precondition is checked on every tick.
Difference between precondition and inverted condition
#include "behaviortree_cpp/bt_factory.h"
void RunTest(BT::Tree& tree)
{
tree.rootBlackboard()->set("check", false);
std::cout << toStr(tree.tickOnce()) << "\n";
tree.rootBlackboard()->set("check", true);
std::cout << toStr(tree.tickOnce()) << "\n";
std::cout << toStr(tree.tickOnce()) << "\n";
tree.rootBlackboard()->set("check", false);
std::cout << toStr(tree.tickOnce()) << "\n";
}
static constexpr auto AlwaysCheckXML = R"(
<root BTCPP_format="4">
<BehaviorTree>
<KeepRunningUntilFailure _skipIf="check == true">
<AlwaysSuccess/>
</KeepRunningUntilFailure>
</BehaviorTree>
</root>
)";
void TestAlwaysCheck()
{
BT::BehaviorTreeFactory factory;
auto tree = factory.createTreeFromText(AlwaysCheckXML);
RunTest(tree);
}
// clang-format off
static constexpr auto SimpleCondition2XML = R"(
<root BTCPP_format="4">
<BehaviorTree>
<Fallback>
<IsCheckSet check="{check}"/>
<KeepRunningUntilFailure>
<AlwaysSuccess/>
</KeepRunningUntilFailure>
</Fallback>
</BehaviorTree>
</root>
)";
// clang-format on
void TestSimpleCondition2()
{
BT::BehaviorTreeFactory factory;
factory.registerSimpleCondition(
"IsCheckSet",
[](BT::TreeNode& node) {
auto check = node.getInput<bool>("check").value();
return check ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
},
BT::PortsList{BT::InputPort("check")});
auto tree = factory.createTreeFromText(SimpleCondition2XML);
RunTest(tree);
}
int main()
{
std::cout << "============= AlwaysCheck =============\n";
TestAlwaysCheck();
std::cout << "============= SimpleCondition =============\n";
TestSimpleCondition2();
return 0;
}
/* Expected output:
============= AlwaysCheck =============
RUNNING
SKIPPED
SKIPPED
RUNNING
============= SimpleCondition =============
RUNNING
RUNNING
RUNNING
RUNNING
*/
Also, when StatefulActionNode receives SKIPPED state on the first iteration, all subsequent ticks are skipped
Unexpected StatefulActionNode behavior
#include "behaviortree_cpp/bt_factory.h"
class MyTestNode : public BT::StatefulActionNode
{
public:
MyTestNode(const std::string& name, const BT::NodeConfig& config) :
BT::StatefulActionNode(name, config){};
static BT::PortsList providedPorts()
{
return {};
}
BT::NodeStatus onStart() override
{
std::cout << "Node started\n";
return BT::NodeStatus::RUNNING;
}
BT::NodeStatus onRunning() override
{
std::cout << "Node running\n";
return BT::NodeStatus::RUNNING;
}
void onHalted() override
{
std::cout << "Node halted\n";
}
};
void RunTest(BT::Tree& tree)
{
tree.rootBlackboard()->set("check", false);
std::cout << toStr(tree.tickOnce()) << "\n";
tree.rootBlackboard()->set("check", true);
std::cout << toStr(tree.tickOnce()) << "\n";
std::cout << toStr(tree.tickOnce()) << "\n";
tree.rootBlackboard()->set("check", false);
std::cout << toStr(tree.tickOnce()) << "\n";
}
// clang-format off
static constexpr auto PreconditionXML = R"(
<root BTCPP_format="4">
<BehaviorTree>
<MyTestNode _skipIf="check!=true"/>
</BehaviorTree>
</root>
)";
// clang-format on
void TestPrecondition()
{
BT::BehaviorTreeFactory factory;
factory.registerNodeType<MyTestNode>("MyTestNode");
auto tree = factory.createTreeFromText(PreconditionXML);
RunTest(tree);
}
// clang-format off
static constexpr auto SimpleConditionXML = R"(
<root BTCPP_format="4">
<BehaviorTree>
<Fallback>
<Inverter>
<IsCheckSet check="{check}"/>
</Inverter>
<MyTestNode/>
</Fallback>
</BehaviorTree>
</root>
)";
// clang-format on
void TestSimpleCondition()
{
BT::BehaviorTreeFactory factory;
factory.registerNodeType<MyTestNode>("MyTestNode");
factory.registerSimpleCondition(
"IsCheckSet",
[](BT::TreeNode& node) {
auto check = node.getInput<bool>("check").value();
return check ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
},
BT::PortsList{BT::InputPort("check")});
auto tree = factory.createTreeFromText(SimpleConditionXML);
RunTest(tree);
}
int main()
{
std::cout << "============= Precondition =============\n";
TestPrecondition();
std::cout << "============= SimpleCondition =============\n";
TestSimpleCondition();
return 0;
}
/* Expected output:
============= Precondition =============
SKIPPED
SKIPPED
SKIPPED
SKIPPED
============= SimpleCondition =============
SUCCESS
Node started
RUNNING
Node running
RUNNING
Node running
RUNNING
Node halted
*/
Metadata
Metadata
Assignees
Labels
No labels