-
Notifications
You must be signed in to change notification settings - Fork 0
added python bindings #8
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: master
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -4,6 +4,7 @@ build* | |
site/* | ||
/.vscode/ | ||
.vs/ | ||
__pycache__ | ||
|
||
# clangd cache | ||
/.cache/* | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,89 @@ | ||
#!/usr/bin/env python3 | ||
|
||
""" | ||
Top-level module of the BehaviorTree.CPP Python bindings. | ||
""" | ||
|
||
# re-export | ||
from btpy_cpp import ( | ||
BehaviorTreeFactory, | ||
NodeStatus, | ||
StatefulActionNode, | ||
SyncActionNode, | ||
Tree, | ||
) | ||
|
||
|
||
def ports(inputs: list[str] = [], outputs: list[str] = []): | ||
"""Decorator to specify input and outputs ports for an action node.""" | ||
|
||
def specify_ports(cls): | ||
cls.input_ports = list(inputs) | ||
cls.output_ports = list(outputs) | ||
return cls | ||
|
||
return specify_ports | ||
|
||
|
||
class AsyncActionNode(StatefulActionNode): | ||
"""An abstract action node implemented via cooperative multitasking. | ||
|
||
Subclasses must implement the `run()` method as a generator. Optionally, | ||
this method can return a final `NodeStatus` value to indicate its exit | ||
condition. | ||
|
||
Optionally, subclasses can override the `on_halted()` method which is called | ||
when the tree halts. The default implementation does nothing. The `run()` | ||
method will never be called again after a halt. | ||
|
||
Note: | ||
It is the responsibility of the action author to not block the main | ||
behavior tree loop with long-running tasks. `yield` calls should be | ||
placed whenever a pause is appropriate. | ||
""" | ||
|
||
def __init__(self, name, config): | ||
super().__init__(name, config) | ||
|
||
def on_start(self) -> NodeStatus: | ||
shaur-k marked this conversation as resolved.
Show resolved
Hide resolved
|
||
self.coroutine = self.run() | ||
return NodeStatus.RUNNING | ||
|
||
def on_running(self) -> NodeStatus: | ||
# The library logic should never allow this to happen, but users can | ||
# still manually call `on_running` without an associated `on_start` | ||
# call. Make sure to print a useful error when this happens. | ||
if self.coroutine is None: | ||
raise "AsyncActionNode run without starting" | ||
|
||
# Resume the coroutine (generator). As long as the generator is not | ||
# exhausted, keep this action in the RUNNING state. | ||
try: | ||
next(self.coroutine) | ||
return NodeStatus.RUNNING | ||
except StopIteration as e: | ||
# If the action returns a status then propagate it upwards. | ||
if e.value is not None: | ||
return e.value | ||
# Otherwise, just assume the action finished successfully. | ||
else: | ||
return NodeStatus.SUCCESS | ||
|
||
def on_halted(self): | ||
# Default action: do nothing | ||
pass | ||
|
||
|
||
# Specify the symbols to be imported with `from btpy import *`, as described in | ||
# [1]. | ||
# | ||
# [1]: https://docs.python.org/3/tutorial/modules.html#importing-from-a-package | ||
__all__ = [ | ||
"ports", | ||
"AsyncActionNode", | ||
"BehaviorTreeFactory", | ||
"NodeStatus", | ||
"StatefulActionNode", | ||
"SyncActionNode", | ||
"Tree", | ||
] |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -2,6 +2,7 @@ | |
gtest/1.14.0 | ||
zeromq/4.3.4 | ||
sqlite3/3.40.1 | ||
pybind11/2.10.4 | ||
|
||
[generators] | ||
CMakeDeps | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,232 @@ | ||
/*************************************************************************** | ||
* Copyright (c) 2019, Martin Renou * | ||
* * | ||
* Distributed under the terms of the BSD 3-Clause License. * | ||
* * | ||
* The full license is in the file LICENSE, distributed with this software. * | ||
****************************************************************************/ | ||
|
||
#ifndef PYBIND11_JSON_HPP | ||
#define PYBIND11_JSON_HPP | ||
|
||
#include <pybind11/pytypes.h> | ||
#include <pybind11/numpy.h> | ||
#include <string> | ||
#include <vector> | ||
|
||
#include "behaviortree_cpp/contrib/json.hpp" | ||
|
||
#include "pybind11/pybind11.h" | ||
|
||
namespace pyjson | ||
{ | ||
namespace py = pybind11; | ||
namespace nl = nlohmann; | ||
|
||
inline py::object from_json(const nl::json& j) | ||
{ | ||
if (j.is_null()) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It feels like you should be able to change this to use a There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. You can even do some sort of mapping of the There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. (and of course if you are returning, the you should use an |
||
{ | ||
return py::none(); | ||
} | ||
else if (j.is_boolean()) | ||
{ | ||
return py::bool_(j.get<bool>()); | ||
} | ||
else if (j.is_number_unsigned()) | ||
{ | ||
return py::int_(j.get<nl::json::number_unsigned_t>()); | ||
} | ||
else if (j.is_number_integer()) | ||
{ | ||
return py::int_(j.get<nl::json::number_integer_t>()); | ||
} | ||
else if (j.is_number_float()) | ||
{ | ||
return py::float_(j.get<double>()); | ||
} | ||
else if (j.is_string()) | ||
{ | ||
return py::str(j.get<std::string>()); | ||
} | ||
else if (j.is_array()) | ||
{ | ||
py::list obj(j.size()); | ||
for (std::size_t i = 0; i < j.size(); i++) | ||
{ | ||
obj[i] = from_json(j[i]); | ||
} | ||
return obj; | ||
} | ||
else // Object | ||
{ | ||
py::dict obj; | ||
for (nl::json::const_iterator it = j.cbegin(); it != j.cend(); ++it) | ||
{ | ||
obj[py::str(it.key())] = from_json(it.value()); | ||
} | ||
return obj; | ||
} | ||
} | ||
|
||
inline nl::json to_json(const py::handle& obj) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Same comment as above, something should be done to simplify this, more to look like a mapping between objects |
||
{ | ||
if (obj.ptr() == nullptr || obj.is_none()) | ||
{ | ||
return nullptr; | ||
} | ||
if (py::isinstance<py::bool_>(obj)) | ||
{ | ||
return obj.cast<bool>(); | ||
} | ||
if (py::isinstance<py::int_>(obj)) | ||
{ | ||
try | ||
{ | ||
nl::json::number_integer_t s = obj.cast<nl::json::number_integer_t>(); | ||
if (py::int_(s).equal(obj)) | ||
{ | ||
return s; | ||
} | ||
} | ||
catch (...) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. usually if you don't swallow the exception? |
||
{ | ||
} | ||
try | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. if you need to keep this structure, wouldn't you merge it with the above |
||
{ | ||
nl::json::number_unsigned_t u = obj.cast<nl::json::number_unsigned_t>(); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. const? |
||
if (py::int_(u).equal(obj)) | ||
{ | ||
return u; | ||
} | ||
} | ||
catch (...) | ||
{ | ||
} | ||
throw std::runtime_error("to_json received an integer out of range for both nl::json::number_integer_t and nl::json::number_unsigned_t type: " + py::repr(obj).cast<std::string>()); | ||
} | ||
if (py::isinstance<py::float_>(obj)) | ||
{ | ||
return obj.cast<double>(); | ||
} | ||
if (py::isinstance<py::bytes>(obj)) | ||
{ | ||
py::module base64 = py::module::import("base64"); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. const? |
||
return base64.attr("b64encode")(obj).attr("decode")("utf-8").cast<std::string>(); | ||
} | ||
if (py::isinstance<py::str>(obj)) | ||
{ | ||
return obj.cast<std::string>(); | ||
} | ||
if (py::isinstance<py::tuple>(obj) || py::isinstance<py::list>(obj)) | ||
{ | ||
auto out = nl::json::array(); | ||
for (const py::handle value : obj) | ||
{ | ||
out.push_back(to_json(value)); | ||
} | ||
return out; | ||
} | ||
if (py::isinstance<py::dict>(obj)) | ||
{ | ||
auto out = nl::json::object(); | ||
for (const py::handle key : obj) | ||
{ | ||
out[py::str(key).cast<std::string>()] = to_json(obj[key]); | ||
} | ||
return out; | ||
} | ||
if (py::isinstance<py::array>(obj)) | ||
{ | ||
return obj.cast<nl::json::array_t>(); | ||
} | ||
throw std::runtime_error("to_json not implemented for this type of object: " + py::repr(obj).cast<std::string>()); | ||
} | ||
} | ||
|
||
// nlohmann_json serializers | ||
namespace nlohmann | ||
{ | ||
namespace py = pybind11; | ||
|
||
#define MAKE_NLJSON_SERIALIZER_DESERIALIZER(T) \ | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Why do these need to be specialized if they're all using the same implementation. Isn't that the point of having a template? |
||
template <> \ | ||
struct adl_serializer<T> \ | ||
{ \ | ||
inline static void to_json(json& j, const T& obj) \ | ||
{ \ | ||
j = pyjson::to_json(obj); \ | ||
} \ | ||
\ | ||
inline static T from_json(const json& j) \ | ||
{ \ | ||
return pyjson::from_json(j); \ | ||
} \ | ||
} | ||
|
||
#define MAKE_NLJSON_SERIALIZER_ONLY(T) \ | ||
template <> \ | ||
struct adl_serializer<T> \ | ||
{ \ | ||
inline static void to_json(json& j, const T& obj) \ | ||
{ \ | ||
j = pyjson::to_json(obj); \ | ||
} \ | ||
} | ||
|
||
MAKE_NLJSON_SERIALIZER_DESERIALIZER(py::object); | ||
|
||
MAKE_NLJSON_SERIALIZER_DESERIALIZER(py::bool_); | ||
MAKE_NLJSON_SERIALIZER_DESERIALIZER(py::int_); | ||
MAKE_NLJSON_SERIALIZER_DESERIALIZER(py::float_); | ||
MAKE_NLJSON_SERIALIZER_DESERIALIZER(py::str); | ||
|
||
MAKE_NLJSON_SERIALIZER_DESERIALIZER(py::list); | ||
MAKE_NLJSON_SERIALIZER_DESERIALIZER(py::tuple); | ||
MAKE_NLJSON_SERIALIZER_DESERIALIZER(py::dict); | ||
|
||
MAKE_NLJSON_SERIALIZER_ONLY(py::handle); | ||
MAKE_NLJSON_SERIALIZER_ONLY(py::detail::item_accessor); | ||
MAKE_NLJSON_SERIALIZER_ONLY(py::detail::list_accessor); | ||
MAKE_NLJSON_SERIALIZER_ONLY(py::detail::tuple_accessor); | ||
MAKE_NLJSON_SERIALIZER_ONLY(py::detail::sequence_accessor); | ||
MAKE_NLJSON_SERIALIZER_ONLY(py::detail::str_attr_accessor); | ||
MAKE_NLJSON_SERIALIZER_ONLY(py::detail::obj_attr_accessor); | ||
|
||
#undef MAKE_NLJSON_SERIALIZER | ||
#undef MAKE_NLJSON_SERIALIZER_ONLY | ||
} | ||
|
||
// pybind11 caster | ||
namespace pybind11 | ||
{ | ||
namespace detail | ||
{ | ||
template <> struct type_caster<nlohmann::json> | ||
{ | ||
public: | ||
PYBIND11_TYPE_CASTER(nlohmann::json, _("json")); | ||
|
||
bool load(handle src, bool) | ||
{ | ||
try | ||
{ | ||
value = pyjson::to_json(src); | ||
return true; | ||
} | ||
catch (...) | ||
{ | ||
return false; | ||
} | ||
} | ||
|
||
static handle cast(nlohmann::json src, return_value_policy /* policy */, handle /* parent */) | ||
{ | ||
object obj = pyjson::from_json(src); | ||
return obj.release(); | ||
} | ||
}; | ||
} | ||
} | ||
|
||
#endif |
Uh oh!
There was an error while loading. Please reload this page.