|
| 1 | +#include "behaviortree_cpp/bt_factory.h" |
| 2 | +#include "behaviortree_cpp/json_export.h" |
| 3 | + |
| 4 | +/** |
| 5 | + * The goal of this tutorial is to show all the possible ways |
| 6 | + * that we can define the default value of a port, i.e. the |
| 7 | + * value that it should have if not specified in the XML |
| 8 | + * */ |
| 9 | + |
| 10 | +// Custom type. to make things more interesting |
| 11 | +struct Point2D |
| 12 | +{ |
| 13 | + int x = 0; |
| 14 | + int y = 0; |
| 15 | + bool operator==(const Point2D& p) const |
| 16 | + { |
| 17 | + return x == p.x && y == p.y; |
| 18 | + } |
| 19 | + bool operator!=(const Point2D& p) const |
| 20 | + { |
| 21 | + return !(*this == p); |
| 22 | + } |
| 23 | +}; |
| 24 | + |
| 25 | +// Allow bi-directional convertion to JSON |
| 26 | +BT_JSON_CONVERTER(Point2D, point) |
| 27 | +{ |
| 28 | + add_field("x", &point.x); |
| 29 | + add_field("y", &point.y); |
| 30 | +} |
| 31 | + |
| 32 | +// We can extend the traditional BT::convertFromString<Point2D>() |
| 33 | +// to support the JSON format too (see port with name "pointE") |
| 34 | +template <> |
| 35 | +[[nodiscard]] Point2D BT::convertFromString<Point2D>(StringView str) |
| 36 | +{ |
| 37 | + if(StartWith(str, "json:")) |
| 38 | + { |
| 39 | + str.remove_prefix(5); |
| 40 | + return convertFromJSON<Point2D>(str); |
| 41 | + } |
| 42 | + const auto parts = BT::splitString(str, ','); |
| 43 | + if(parts.size() != 2) |
| 44 | + { |
| 45 | + throw BT::RuntimeError("invalid input)"); |
| 46 | + } |
| 47 | + int x = convertFromString<int>(parts[0]); |
| 48 | + int y = convertFromString<int>(parts[1]); |
| 49 | + return { x, y }; |
| 50 | +} |
| 51 | + |
| 52 | +//----------------------------------------------- |
| 53 | +using namespace BT; |
| 54 | + |
| 55 | +class NodeWithDefaultPoints : public SyncActionNode |
| 56 | +{ |
| 57 | +public: |
| 58 | + NodeWithDefaultPoints(const std::string& name, const NodeConfig& config) |
| 59 | + : SyncActionNode(name, config) |
| 60 | + {} |
| 61 | + |
| 62 | + NodeStatus tick() override |
| 63 | + { |
| 64 | + // Let0s check if all the portas have the expected value |
| 65 | + Point2D pointA, pointB, pointC, pointD, pointE, input; |
| 66 | + |
| 67 | + if(!getInput("pointA", pointA) || pointA != Point2D{ 1, 2 }) |
| 68 | + { |
| 69 | + throw std::runtime_error("failed pointA"); |
| 70 | + } |
| 71 | + if(!getInput("pointB", pointB) || pointB != Point2D{ 3, 4 }) |
| 72 | + { |
| 73 | + throw std::runtime_error("failed pointB"); |
| 74 | + } |
| 75 | + if(!getInput("pointC", pointC) || pointC != Point2D{ 5, 6 }) |
| 76 | + { |
| 77 | + throw std::runtime_error("failed pointC"); |
| 78 | + } |
| 79 | + if(!getInput("pointD", pointD) || pointD != Point2D{ 7, 8 }) |
| 80 | + { |
| 81 | + throw std::runtime_error("failed pointD"); |
| 82 | + } |
| 83 | + if(!getInput("pointE", pointE) || pointE != Point2D{ 9, 10 }) |
| 84 | + { |
| 85 | + throw std::runtime_error("failed pointE"); |
| 86 | + } |
| 87 | + if(!getInput("input", input) || input != Point2D{ -1, -2 }) |
| 88 | + { |
| 89 | + throw std::runtime_error("failed input"); |
| 90 | + } |
| 91 | + return NodeStatus::SUCCESS; |
| 92 | + } |
| 93 | + |
| 94 | + static PortsList providedPorts() |
| 95 | + { |
| 96 | + return { BT::InputPort<Point2D>("input", "no default value"), |
| 97 | + BT::InputPort<Point2D>("pointA", Point2D{ 1, 2 }, "default value is [1,2]"), |
| 98 | + BT::InputPort<Point2D>("pointB", "{point}", |
| 99 | + "default value inside blackboard {point}"), |
| 100 | + BT::InputPort<Point2D>("pointC", "5,6", "default value is [5,6]"), |
| 101 | + BT::InputPort<Point2D>("pointD", "{=}", |
| 102 | + "default value inside blackboard {pointD}"), |
| 103 | + BT::InputPort<Point2D>("pointE", R"(json:{"x":9,"y":10})", |
| 104 | + "default value is [9,10]") }; |
| 105 | + } |
| 106 | +}; |
| 107 | + |
| 108 | +int main() |
| 109 | +{ |
| 110 | + std::string xml_txt = R"( |
| 111 | + <root BTCPP_format="4" > |
| 112 | + <BehaviorTree> |
| 113 | + <NodeWithDefaultPoints input="-1,-2"/> |
| 114 | + </BehaviorTree> |
| 115 | + </root>)"; |
| 116 | + |
| 117 | + JsonExporter::get().addConverter<Point2D>(); |
| 118 | + |
| 119 | + BehaviorTreeFactory factory; |
| 120 | + factory.registerNodeType<NodeWithDefaultPoints>("NodeWithDefaultPoints"); |
| 121 | + auto tree = factory.createTreeFromText(xml_txt); |
| 122 | + |
| 123 | + tree.subtrees.front()->blackboard->set<Point2D>("point", Point2D{ 3, 4 }); |
| 124 | + tree.subtrees.front()->blackboard->set<Point2D>("pointD", Point2D{ 7, 8 }); |
| 125 | + |
| 126 | + BT::NodeStatus status = tree.tickOnce(); |
| 127 | + std::cout << "Result: " << toStr(status) << std::endl; |
| 128 | + |
| 129 | + return 0; |
| 130 | +} |
0 commit comments