|
| 1 | +#include <memory> |
| 2 | + |
| 3 | +#include <pybind11/pybind11.h> |
| 4 | +#include <pybind11/gil.h> |
| 5 | +#include <pybind11/eval.h> |
| 6 | +#include <pybind11/chrono.h> |
| 7 | +#include <pybind11/pytypes.h> |
| 8 | +#include <pybind11/stl.h> |
| 9 | + |
| 10 | +#include "behaviortree_cpp/basic_types.h" |
| 11 | +#include "behaviortree_cpp/bt_factory.h" |
| 12 | +#include "behaviortree_cpp/action_node.h" |
| 13 | +#include "behaviortree_cpp/tree_node.h" |
| 14 | + |
| 15 | +namespace BT |
| 16 | +{ |
| 17 | + |
| 18 | +namespace py = pybind11; |
| 19 | + |
| 20 | +class Py_SyncActionNode : public SyncActionNode |
| 21 | +{ |
| 22 | +public: |
| 23 | + Py_SyncActionNode(const std::string& name, const NodeConfig& config) : |
| 24 | + SyncActionNode(name, config) |
| 25 | + {} |
| 26 | + |
| 27 | + NodeStatus tick() override |
| 28 | + { |
| 29 | + py::gil_scoped_acquire gil; |
| 30 | + return py::get_overload(this, "tick")().cast<NodeStatus>(); |
| 31 | + } |
| 32 | + |
| 33 | + py::object Py_getInput(const std::string& name) |
| 34 | + { |
| 35 | + py::object obj; |
| 36 | + getInput(name, obj); |
| 37 | + return obj; |
| 38 | + } |
| 39 | + |
| 40 | + void Py_setOutput(const std::string& name, const py::object& value) |
| 41 | + { |
| 42 | + setOutput(name, value); |
| 43 | + } |
| 44 | +}; |
| 45 | + |
| 46 | +// Add a conversion specialization from string values into general py::objects |
| 47 | +// by evaluating as a Python expression. |
| 48 | +template <> |
| 49 | +inline py::object convertFromString(StringView str) |
| 50 | +{ |
| 51 | + try |
| 52 | + { |
| 53 | + // First, try evaluating the string as-is. Maybe it's a number, a list, a |
| 54 | + // dict, an object, etc. |
| 55 | + return py::eval(str); |
| 56 | + } |
| 57 | + catch (py::error_already_set& e) |
| 58 | + { |
| 59 | + // If that fails, then assume it's a string literal with quotation marks |
| 60 | + // omitted. |
| 61 | + return py::str(str); |
| 62 | + } |
| 63 | +} |
| 64 | + |
| 65 | +PYBIND11_MODULE(btpy_cpp, m) |
| 66 | +{ |
| 67 | + py::class_<PortInfo>(m, "PortInfo"); |
| 68 | + m.def("input_port", |
| 69 | + [](const std::string& name) { return InputPort<py::object>(name); }); |
| 70 | + m.def("output_port", |
| 71 | + [](const std::string& name) { return OutputPort<py::object>(name); }); |
| 72 | + |
| 73 | + m.def( |
| 74 | + "ports2", |
| 75 | + [](const py::list& inputs, const py::list& outputs) -> auto { |
| 76 | + return [](py::type type) -> auto { return type; }; |
| 77 | + }, |
| 78 | + py::kw_only(), py::arg("inputs") = py::none(), py::arg("outputs") = py::none()); |
| 79 | + |
| 80 | + py::class_<BehaviorTreeFactory>(m, "BehaviorTreeFactory") |
| 81 | + .def(py::init()) |
| 82 | + .def("register", |
| 83 | + [](BehaviorTreeFactory& factory, const py::type type) { |
| 84 | + const std::string name = type.attr("__name__").cast<std::string>(); |
| 85 | + |
| 86 | + TreeNodeManifest manifest; |
| 87 | + manifest.type = NodeType::ACTION; |
| 88 | + manifest.registration_ID = name; |
| 89 | + manifest.ports = {}; |
| 90 | + manifest.description = ""; |
| 91 | + |
| 92 | + const auto input_ports = type.attr("input_ports").cast<py::list>(); |
| 93 | + for (const auto& name : input_ports) |
| 94 | + { |
| 95 | + manifest.ports.insert(InputPort<py::object>(name.cast<std::string>())); |
| 96 | + } |
| 97 | + |
| 98 | + const auto output_ports = type.attr("output_ports").cast<py::list>(); |
| 99 | + for (const auto& name : output_ports) |
| 100 | + { |
| 101 | + manifest.ports.insert(OutputPort<py::object>(name.cast<std::string>())); |
| 102 | + } |
| 103 | + |
| 104 | + factory.registerBuilder( |
| 105 | + manifest, |
| 106 | + [type](const std::string& name, |
| 107 | + const NodeConfig& config) -> std::unique_ptr<TreeNode> { |
| 108 | + py::object obj = type(name, config); |
| 109 | + // TODO: Increment the object's reference count or else it |
| 110 | + // will be GC'd at the end of this scope. The downside is |
| 111 | + // that, unless we can decrement the ref when the unique_ptr |
| 112 | + // is destroyed, then the object will live forever. |
| 113 | + obj.inc_ref(); |
| 114 | + |
| 115 | + return std::unique_ptr<Py_SyncActionNode>( |
| 116 | + obj.cast<Py_SyncActionNode*>()); |
| 117 | + }); |
| 118 | + }) |
| 119 | + .def("create_tree_from_text", |
| 120 | + [](BehaviorTreeFactory& factory, const std::string& text) -> Tree { |
| 121 | + return factory.createTreeFromText(text); |
| 122 | + }); |
| 123 | + |
| 124 | + py::class_<Tree>(m, "Tree") |
| 125 | + .def("tick_once", &Tree::tickOnce) |
| 126 | + .def("tick_exactly_once", &Tree::tickExactlyOnce) |
| 127 | + .def("tick_while_running", &Tree::tickWhileRunning, |
| 128 | + py::arg("sleep_time") = std::chrono::milliseconds(10)); |
| 129 | + |
| 130 | + py::enum_<NodeStatus>(m, "NodeStatus") |
| 131 | + .value("SUCCESS", NodeStatus::SUCCESS) |
| 132 | + .value("FAILURE", NodeStatus::FAILURE) |
| 133 | + .value("IDLE", NodeStatus::IDLE) |
| 134 | + .value("RUNNING", NodeStatus::RUNNING) |
| 135 | + .value("SKIPPED", NodeStatus::SKIPPED) |
| 136 | + .export_values(); |
| 137 | + |
| 138 | + py::class_<NodeConfig>(m, "NodeConfig"); |
| 139 | + |
| 140 | + py::class_<Py_SyncActionNode>(m, "SyncActionNode") |
| 141 | + .def(py::init<const std::string&, const NodeConfig&>()) |
| 142 | + .def("tick", &Py_SyncActionNode::tick) |
| 143 | + .def("get_input", &Py_SyncActionNode::Py_getInput) |
| 144 | + .def("set_output", &Py_SyncActionNode::Py_setOutput); |
| 145 | +} |
| 146 | + |
| 147 | +} // namespace BT |
0 commit comments