Skip to content

Commit

Permalink
DNM Fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
EricCousineau-TRI committed Nov 11, 2018
1 parent 6abdcf3 commit 6770690
Show file tree
Hide file tree
Showing 14 changed files with 241 additions and 292 deletions.
15 changes: 8 additions & 7 deletions bindings/pybind11_ext/numpy_dtypes_user.h
Original file line number Diff line number Diff line change
Expand Up @@ -368,8 +368,8 @@ class dtype_user : public object {
using Class = Class_;
using DTypePyObject = detail::dtype_user_instance<Class>;

dtype_user(handle scope, const char* name) : cls_(none()) {
register_type(name);
dtype_user(handle scope, const char* name, const char* doc = "") : cls_(none()) {
register_type(name, doc);
scope.attr(name) = self();
auto& entry = detail::dtype_info::get_mutable_entry<Class>(true);
entry.cls = self();
Expand Down Expand Up @@ -411,14 +411,14 @@ class dtype_user : public object {
}

template <typename ... Args>
dtype_user& def(detail::initimpl::constructor<Args...>&&) {
dtype_user& def(detail::initimpl::constructor<Args...>&&, const char* doc = "") {
// See notes in `add_init`.
// N.B. Do NOT use `Class*` as the argument, since that may incur recursion.
add_init([](object py_self, Args... args) {
// Old-style. No factories for now.
Class* self = DTypePyObject::load_raw(py_self.ptr());
new (self) Class(std::forward<Args>(args)...);
});
}, doc);
return *this;
}

Expand Down Expand Up @@ -547,7 +547,7 @@ class dtype_user : public object {
}

template <typename Func>
void add_init(Func&& f) {
void add_init(Func&& f, const char* doc) {
// Do not construct this with the name `__init__` as `cpp_function` will
// try to have this register the instance, and most likely segfault.
this->def("_dtype_init", std::forward<Func>(f));
Expand All @@ -559,7 +559,7 @@ class dtype_user : public object {
[init](handle self, args args, kwargs kwargs) {
// Dispatch.
init(self, *args, **kwargs);
}, is_method(self()));
}, is_method(self()), doc);
self().attr("__init__") = func;
}
}
Expand Down Expand Up @@ -606,7 +606,7 @@ class dtype_user : public object {
return 1;
}

void register_type(const char* name) {
void register_type(const char* name, const char* doc) {
// Ensure we initialize NumPy before accessing `PyGenericArrType_Type`.
auto& api = detail::npy_api::get();
// Loosely uses https://stackoverflow.com/a/12505371/7829525 as well.
Expand All @@ -624,6 +624,7 @@ class dtype_user : public object {
ClassObject_Type.tp_basicsize = sizeof(DTypePyObject);
ClassObject_Type.tp_getset = 0;
ClassObject_Type.tp_flags = Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HEAPTYPE;
ClassObject_Type.tp_doc = doc;
if (PyType_Ready(&ClassObject_Type) != 0)
pybind11_fail("dtype_user: Unable to initialize class");
// TODO(eric.cousineau): Figure out how to catch recursions with
Expand Down
24 changes: 24 additions & 0 deletions bindings/pydrake/_symbolic_extra.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,30 @@
# rationale.
import functools

# Import aliases.
# TODO(eric.cousineau): Deprecate, then remove these in lieu of `np.{func}`
from pydrake.math import (
log,
abs,
exp,
pow,
sqrt,
sin,
cos,
tan,
asin,
acos,
atan,
atan2,
sinh,
cosh,
tanh,
min,
max,
ceil,
floor
)


def logical_and(*formulas):
assert len(formulas) >= 1, "Must supply at least one operand"
Expand Down
179 changes: 86 additions & 93 deletions bindings/pydrake/autodiffutils_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,103 +29,96 @@ PYBIND11_MODULE(autodiffutils, m) {

py::dtype_user<AutoDiffXd> autodiff(m, "AutoDiffXd");
DefImplicitConversionsFromNumericTypes(&autodiff);
autodiff
.def(py::init<double>())
.def(py::init<const double&, const Eigen::VectorXd&>())
// Downcasting must be explicit, to prevent inadvertent information loss.
.def_loop(py::dtype_method::explicit_conversion(
[](const AutoDiffXd& self) -> double { return self.value(); }))
// General methods.
.def("value", [](const AutoDiffXd& self) {
return self.value();
})
.def("derivatives", [](const AutoDiffXd& self) {
return self.derivatives();
})
.def("__str__", [](const AutoDiffXd& self) {
return py::str("AD{{{}, nderiv={}}}").format(
self.value(), self.derivatives().size());
})
.def("__repr__", [](const AutoDiffXd& self) {
return py::str("<AutoDiffXd {} nderiv={}>").format(
self.value(), self.derivatives().size());
})
// Arithmetic
.def_loop(-py::self)
.def_loop(py::self + py::self)
.def_loop(py::self + double())
.def_loop(double() + py::self)
.def_loop(py::self - py::self)
.def_loop(py::self - double())
.def_loop(double() - py::self)
.def_loop(py::self * py::self)
.def_loop(py::self * double())
.def_loop(double() * py::self)
.def_loop(py::self / py::self)
.def_loop(py::self / double())
.def_loop(double() / py::self)
// Logical comparison
.def_loop(py::self == py::self)
.def_loop(py::self == double())
.def_loop(py::self != py::self)
.def_loop(py::self != double())
// .def_loop(double() != py::self)
.def_loop(py::self < py::self)
.def_loop(py::self < double())
.def_loop(double() < py::self)
.def_loop(py::self <= py::self)
.def_loop(py::self <= double())
.def_loop(double() <= py::self)
.def_loop(py::self > py::self)
.def_loop(py::self > double())
.def_loop(double() > py::self)
.def_loop(py::self >= py::self)
.def_loop(py::self >= double())
.def_loop(double() >= py::self)
// Dot-product
.def_loop(py::dtype_method::dot())
// N.B. Certain versions of NumPy require `square` be specifically
// defined.
.def_loop("square", [](const AutoDiffXd& self) {
return self * self;
})
.def_loop("isfinite", [](const AutoDiffXd& self) {
return isfinite(self.value());
});
autodiff // BR
.def(py::init<double>())
.def(py::init<const double&, const Eigen::VectorXd&>())
// Downcasting must be explicit, to prevent inadvertent information loss.
.def_loop(py::dtype_method::explicit_conversion(
[](const AutoDiffXd& self) -> double { return self.value(); }))
// General methods.
.def("value", [](const AutoDiffXd& self) { return self.value(); })
.def("derivatives",
[](const AutoDiffXd& self) { return self.derivatives(); })
.def("__str__",
[](const AutoDiffXd& self) {
return py::str("AD{{{}, nderiv={}}}")
.format(self.value(), self.derivatives().size());
})
.def("__repr__",
[](const AutoDiffXd& self) {
return py::str("<AutoDiffXd {} nderiv={}>")
.format(self.value(), self.derivatives().size());
})
// Arithmetic
.def_loop(-py::self)
.def_loop(py::self + py::self)
.def_loop(py::self + double())
.def_loop(double() + py::self)
.def_loop(py::self - py::self)
.def_loop(py::self - double())
.def_loop(double() - py::self)
.def_loop(py::self * py::self)
.def_loop(py::self * double())
.def_loop(double() * py::self)
.def_loop(py::self / py::self)
.def_loop(py::self / double())
.def_loop(double() / py::self)
// Logical comparison
.def_loop(py::self == py::self)
.def_loop(py::self == double())
.def_loop(py::self != py::self)
.def_loop(py::self != double())
// .def_loop(double() != py::self)
.def_loop(py::self < py::self)
.def_loop(py::self < double())
.def_loop(double() < py::self)
.def_loop(py::self <= py::self)
.def_loop(py::self <= double())
.def_loop(double() <= py::self)
.def_loop(py::self > py::self)
.def_loop(py::self > double())
.def_loop(double() > py::self)
.def_loop(py::self >= py::self)
.def_loop(py::self >= double())
.def_loop(double() >= py::self)
// Dot-product
.def_loop(py::dtype_method::dot())
// N.B. Certain versions of NumPy require `square` be specifically
// defined.
.def_loop("square", [](const AutoDiffXd& self) { return self * self; })
.def_loop("isfinite",
[](const AutoDiffXd& self) { return isfinite(self.value()); });

// Add overloads for `math` functions.
auto math = py::module::import("pydrake.math");
UfuncMirrorDef<decltype(autodiff)>(&autodiff, math)
.def_loop("__pow__", "pow",
[](const AutoDiffXd& base, int exponent) {
return pow(base, exponent);
})
.def_loop("__abs__", "abs", [](const AutoDiffXd& x) { return abs(x); })
.def_loop("log", [](const AutoDiffXd& x) { return log(x); })
.def_loop("exp", [](const AutoDiffXd& x) { return exp(x); })
.def_loop("sqrt", [](const AutoDiffXd& x) { return sqrt(x); })
.def_loop("sin", [](const AutoDiffXd& x) { return sin(x); })
.def_loop("cos", [](const AutoDiffXd& x) { return cos(x); })
.def_loop("tan", [](const AutoDiffXd& x) { return tan(x); })
.def_loop("arcsin", "asin", [](const AutoDiffXd& x) { return asin(x); })
.def_loop("arccos", "acos", [](const AutoDiffXd& x) { return acos(x); })
.def_loop("arctan2", "atan2",
[](const AutoDiffXd& y, const AutoDiffXd& x) {
return atan2(y, x);
})
.def_loop("sinh", [](const AutoDiffXd& x) { return sinh(x); })
.def_loop("cosh", [](const AutoDiffXd& x) { return cosh(x); })
.def_loop("tanh", [](const AutoDiffXd& x) { return tanh(x); })
.def_loop("fmin", "min",
[](const AutoDiffXd& x, const AutoDiffXd& y) {
return min(x, y);
})
.def_loop("fmax", "max",
[](const AutoDiffXd& x, const AutoDiffXd& y) {
return max(x, y);
})
.def_loop("ceil", [](const AutoDiffXd& x) { return ceil(x); })
.def_loop("floor", [](const AutoDiffXd& x) { return floor(x); });
.def_loop("__pow__", "pow",
[](const AutoDiffXd& base, int exponent) {
return pow(base, exponent);
})
.def_loop("__abs__", "abs", [](const AutoDiffXd& x) { return abs(x); })
.def_loop("log", [](const AutoDiffXd& x) { return log(x); })
.def_loop("exp", [](const AutoDiffXd& x) { return exp(x); })
.def_loop("sqrt", [](const AutoDiffXd& x) { return sqrt(x); })
.def_loop("sin", [](const AutoDiffXd& x) { return sin(x); })
.def_loop("cos", [](const AutoDiffXd& x) { return cos(x); })
.def_loop("tan", [](const AutoDiffXd& x) { return tan(x); })
.def_loop("arcsin", "asin", [](const AutoDiffXd& x) { return asin(x); })
.def_loop("arccos", "acos", [](const AutoDiffXd& x) { return acos(x); })
.def_loop(
"arctan2", "atan2",
[](const AutoDiffXd& y, const AutoDiffXd& x) { return atan2(y, x); })
.def_loop("sinh", [](const AutoDiffXd& x) { return sinh(x); })
.def_loop("cosh", [](const AutoDiffXd& x) { return cosh(x); })
.def_loop("tanh", [](const AutoDiffXd& x) { return tanh(x); })
.def_loop(
"fmin", "min",
[](const AutoDiffXd& x, const AutoDiffXd& y) { return min(x, y); })
.def_loop(
"fmax", "max",
[](const AutoDiffXd& x, const AutoDiffXd& y) { return max(x, y); })
.def_loop("ceil", [](const AutoDiffXd& x) { return ceil(x); })
.def_loop("floor", [](const AutoDiffXd& x) { return floor(x); });
}

} // namespace pydrake
Expand Down
6 changes: 4 additions & 2 deletions bindings/pydrake/pydrake_pybind.h
Original file line number Diff line number Diff line change
Expand Up @@ -276,7 +276,8 @@ This is a brief recipe for debugging with GDB
source_dir=${workspace}/bazel-${name}
source /tmp/env.sh
cd ${target_bin_path}.runfiles/${name}
gdb --directory ${source_dir} --args python ${target_bin_path} --trace=user -f
gdb --directory ${source_dir} --args python ${target_bin_path}
--trace=user -f
)
This allows you to use GDB from the terminal, while being able to inspect the
Expand Down Expand Up @@ -333,7 +334,8 @@ template <typename PyClass>
void DefCopyAndDeepCopy(PyClass* ppy_class) {
using Class = typename PyClass::type;
PyClass& py_class = *ppy_class;
py_class.def("__copy__", [](const Class* self) { return Class{*self}; })
py_class // BR
.def("__copy__", [](const Class* self) { return Class{*self}; })
.def("__deepcopy__",
[](const Class* self, py::dict /* memo */) { return Class{*self}; });
}
Expand Down
Loading

0 comments on commit 6770690

Please sign in to comment.