|
16 | 16 | #include <behaviortree_cpp/loggers/bt_cout_logger.h> |
17 | 17 | #include <behaviortree_cpp/loggers/groot2_publisher.h> |
18 | 18 | #include <behaviortree_cpp/tree_node.h> |
| 19 | +#include <behaviortree_py/behaviortree_py.hpp> |
19 | 20 |
|
20 | 21 | namespace py = pybind11; |
21 | 22 | using namespace BT; |
@@ -49,26 +50,7 @@ PYBIND11_MODULE(behaviortree_py, m) { |
49 | 50 | py::class_<TreeNode, std::shared_ptr<TreeNode>>(m, "TreeNode") |
50 | 51 | .def("name", &TreeNode::name) |
51 | 52 | .def("status", &TreeNode::status) |
52 | | - .def("type", &TreeNode::type) |
53 | | - .def("get_input_string", |
54 | | - [](TreeNode *self, const std::string &key) { |
55 | | - return self->getInput<std::string>(key).value(); |
56 | | - }) |
57 | | - .def("get_input_int", |
58 | | - [](TreeNode *self, const std::string &key) { |
59 | | - return self->getInput<int>(key).value(); |
60 | | - }) |
61 | | - .def("get_input_double", |
62 | | - [](TreeNode *self, const std::string &key) { |
63 | | - return self->getInput<double>(key).value(); |
64 | | - }) |
65 | | - .def("set_output", |
66 | | - py::overload_cast<const std::string &, const std::string &>( |
67 | | - &TreeNode::setOutput<std::string>)) |
68 | | - .def("set_output", py::overload_cast<const std::string &, const int &>( |
69 | | - &TreeNode::setOutput<int>)) |
70 | | - .def("set_output", py::overload_cast<const std::string &, const double &>( |
71 | | - &TreeNode::setOutput<double>)); |
| 53 | + .def("type", &TreeNode::type); |
72 | 54 |
|
73 | 55 | py::class_<BehaviorTreeFactory>(m, "BehaviorTreeFactory") |
74 | 56 | .def(py::init<>()) |
@@ -144,40 +126,8 @@ PYBIND11_MODULE(behaviortree_py, m) { |
144 | 126 | }, |
145 | 127 | py::arg("root_tree")); |
146 | 128 |
|
147 | | - m.def( |
148 | | - "input_port_int", |
149 | | - [](BT::StringView name, BT::StringView description) { |
150 | | - return BT::InputPort<int>(name, description); |
151 | | - }, |
152 | | - py::arg("name"), py::arg("description") = "") |
153 | | - .def( |
154 | | - "input_port_double", |
155 | | - [](BT::StringView name, BT::StringView description) { |
156 | | - return BT::InputPort<double>(name, description); |
157 | | - }, |
158 | | - py::arg("name"), py::arg("description") = "") |
159 | | - .def( |
160 | | - "input_port_string", |
161 | | - [](BT::StringView name, BT::StringView description) { |
162 | | - return BT::InputPort<std::string>(name, description); |
163 | | - }, |
164 | | - py::arg("name"), py::arg("description") = "") |
165 | | - .def( |
166 | | - "output_port_int", |
167 | | - [](BT::StringView name, BT::StringView description) { |
168 | | - return BT::OutputPort<int>(name, description); |
169 | | - }, |
170 | | - py::arg("name"), py::arg("description") = "") |
171 | | - .def( |
172 | | - "output_port_double", |
173 | | - [](BT::StringView name, BT::StringView description) { |
174 | | - return BT::OutputPort<double>(name, description); |
175 | | - }, |
176 | | - py::arg("name"), py::arg("description") = "") |
177 | | - .def( |
178 | | - "output_port_string", |
179 | | - [](BT::StringView name, BT::StringView description) { |
180 | | - return BT::OutputPort<std::string>(name, description); |
181 | | - }, |
182 | | - py::arg("name"), py::arg("description") = ""); |
| 129 | + bind_port_methods<int>(m, "int"); |
| 130 | + bind_port_methods<double>(m, "double"); |
| 131 | + bind_port_methods<std::string>(m, "string"); |
| 132 | + bind_port_methods<bool>(m, "bool"); |
183 | 133 | } |
0 commit comments