Skip to content

Commit

Permalink
fixup! target existing spaghetti code
Browse files Browse the repository at this point in the history
  • Loading branch information
EricCousineau-TRI authored and soonho-tri committed May 12, 2021
1 parent d9074e3 commit 9356274
Show file tree
Hide file tree
Showing 4 changed files with 54 additions and 68 deletions.
5 changes: 4 additions & 1 deletion bindings/pydrake/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,10 @@ drake_cc_library(
hdrs = ["symbolic_types_pybind.h"],
declare_installed_headers = 0,
visibility = ["//visibility:public"],
deps = ["//:drake_shared_library"],
deps = [
"//:drake_shared_library",
"//bindings/pydrake:documentation_pybind",
],
)

drake_pybind_library(
Expand Down
3 changes: 2 additions & 1 deletion bindings/pydrake/math_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ namespace pydrake {

using std::pow;
using symbolic::Expression;
using symbolic::Variable;

namespace {
template <typename T>
Expand Down Expand Up @@ -474,7 +475,7 @@ void DoScalarIndependentDefinitions(py::module m) {

// See TODO in corresponding header file - these should be removed soon!
pydrake::internal::BindAutoDiffMathOverloads(&m);
pydrake::internal::BindSymbolicMathOverloads(&m);
pydrake::internal::BindSymbolicMathOverloads<Expression>(&m);
}
} // namespace

Expand Down
42 changes: 4 additions & 38 deletions bindings/pydrake/symbolic_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -116,20 +116,6 @@ PYBIND11_MODULE(symbolic, m) {
return pow(self, other);
},
py::is_operator())
// We add the following methods (exp, sqrt, sin, cos, tan, arcsin, arccos,
// arctan, sinh, cosh, tanh) to support corresponding numpy functions such
// as np.sin(x).
.def("exp", [](const Variable& self) { return exp(self); })
.def("sqrt", [](const Variable& self) { return sqrt(self); })
.def("sin", [](const Variable& self) { return sin(self); })
.def("cos", [](const Variable& self) { return cos(self); })
.def("tan", [](const Variable& self) { return tan(self); })
.def("arcsin", [](const Variable& self) { return asin(self); })
.def("arccos", [](const Variable& self) { return acos(self); })
.def("arctan", [](const Variable& self) { return atan(self); })
.def("sinh", [](const Variable& self) { return sinh(self); })
.def("cosh", [](const Variable& self) { return cosh(self); })
.def("tanh", [](const Variable& self) { return tanh(self); })
// We add `EqualTo` instead of `equal_to` to maintain consistency among
// symbolic classes (Variable, Expression, Formula, Polynomial) on Python
// side. This enables us to achieve polymorphism via ducktyping in Python.
Expand Down Expand Up @@ -164,6 +150,7 @@ PYBIND11_MODULE(symbolic, m) {
.def(py::self != Expression())
.def(py::self != py::self)
.def(py::self != double());
internal::BindSymbolicMathOverloads<Variable>(&var_cls);
DefCopyAndDeepCopy(&var_cls);

// Bind the free functions for MakeVectorXXXVariable
Expand Down Expand Up @@ -420,35 +407,14 @@ PYBIND11_MODULE(symbolic, m) {
.def(py::self != double())
.def("Differentiate", &Expression::Differentiate,
doc.Expression.Differentiate.doc)
.def("Jacobian", &Expression::Jacobian, doc.Expression.Jacobian.doc)
// TODO(eric.cousineau): Figure out how to consolidate with the `math`
// methods.
.def("log", &symbolic::log, doc.log.doc)
.def("__abs__", &symbolic::abs)
.def("exp", &symbolic::exp, doc.exp.doc)
.def("sqrt", &symbolic::sqrt, doc.sqrt.doc)
// TODO(eric.cousineau): Move `__pow__` here.
.def("sin", &symbolic::sin, doc.sin.doc)
.def("cos", &symbolic::cos, doc.cos.doc)
.def("tan", &symbolic::tan, doc.tan.doc)
.def("arcsin", &symbolic::asin, doc.asin.doc)
.def("arccos", &symbolic::acos, doc.acos.doc)
.def("arctan2", &symbolic::atan2, doc.atan2.doc)
.def("sinh", &symbolic::sinh, doc.sinh.doc)
.def("cosh", &symbolic::cosh, doc.cosh.doc)
.def("tanh", &symbolic::tanh, doc.tanh.doc)
.def("min", &symbolic::min, doc.min.doc)
.def("max", &symbolic::max, doc.max.doc)
.def("ceil", &symbolic::ceil, doc.ceil.doc)
.def("__ceil__", &symbolic::ceil, doc.ceil.doc)
.def("floor", &symbolic::floor, doc.floor.doc)
.def("__floor__", &symbolic::floor, doc.floor.doc);
.def("Jacobian", &Expression::Jacobian, doc.Expression.Jacobian.doc);
pydrake::internal::BindSymbolicMathOverloads<Expression>(&expr_cls);
DefCopyAndDeepCopy(&expr_cls);

// TODO(eric.cousineau): These should actually exist on the class, and should
// be should be consolidated with the above repeated definitions. This would
// yield the same parity with AutoDiff.
pydrake::internal::BindSymbolicMathOverloads(&m);
pydrake::internal::BindSymbolicMathModuleOverloads(m);

m.def("if_then_else", &symbolic::if_then_else);

Expand Down
72 changes: 44 additions & 28 deletions bindings/pydrake/symbolic_types_pybind.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include "pybind11/eigen.h"
#include "pybind11/pybind11.h"

#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
#include "drake/common/symbolic.h"

Expand All @@ -25,44 +26,59 @@ namespace internal {
// TODO(eric.cousineau): Deprecate these methods once we support proper NumPy
// UFuncs.

// TODO(eric.cousineau): Per TODO in `symbolic_py.cc`, ensure that this binds
// directly to the class, so it is the same as AutoDiff.
// Adds math function overloads for Expression (ADL free functions from
// `symbolic_expression.h`) for both NumPy methods and `pydrake.math`.
// @param obj
// This is used to register functions or overloads in either (a)
// This is used to register functions or overloads in either
// `pydrake.symbolic` or `pydrake.math`.
template <typename PyObject>
template <typename Class, typename PyObject>
void BindSymbolicMathOverloads(PyObject* obj) {
using symbolic::Expression;
constexpr auto& doc = pydrake_doc.drake.symbolic;
(*obj) // BR
.def("log", &symbolic::log)
.def("abs", &symbolic::abs)
.def("exp", &symbolic::exp)
.def("sqrt", &symbolic::sqrt)
.def("log", &symbolic::log, doc.log.doc)
.def("abs", &symbolic::abs, doc.abs.doc)
.def("__abs__", &symbolic::abs, doc.abs.doc)
.def("exp", &symbolic::exp, doc.exp.doc)
.def("sqrt", &symbolic::sqrt, doc.sqrt.doc)
.def("pow",
[](const Expression& base, const Expression& exponent) {
[](const Class& base, const Expression& exponent) {
return pow(base, exponent);
})
.def("sin", &symbolic::sin)
.def("cos", &symbolic::cos)
.def("tan", &symbolic::tan)
.def("asin", &symbolic::asin)
.def("acos", &symbolic::acos)
.def("atan", &symbolic::atan)
.def("atan2", &symbolic::atan2)
.def("sinh", &symbolic::sinh)
.def("cosh", &symbolic::cosh)
.def("tanh", &symbolic::tanh)
.def("min", &symbolic::min)
.def("max", &symbolic::max)
.def("ceil", &symbolic::ceil)
.def("floor", &symbolic::floor)
// TODO(eric.cousineau): This is not a NumPy-overridable method using
// dtype=object. Deprecate and move solely into `pydrake.math`.
.def("inv", [](const MatrixX<Expression>& X) -> MatrixX<Expression> {
return X.inverse();
});
.def("sin", &symbolic::sin, doc.sin.doc)
.def("cos", &symbolic::cos, doc.cos.doc)
.def("tan", &symbolic::tan, doc.tan.doc)
.def("arcsin", &symbolic::asin, doc.asin.doc)
.def("asin", &symbolic::asin, doc.asin.doc)
.def("arccos", &symbolic::acos, doc.acos.doc)
.def("acos", &symbolic::acos, doc.acos.doc)
.def("arctan", &symbolic::atan, doc.atan.doc)
.def("atan", &symbolic::atan, doc.atan.doc)
.def("arctan2", &symbolic::atan2, doc.atan2.doc)
.def("atan2", &symbolic::atan2, doc.atan2.doc)
.def("sinh", &symbolic::sinh, doc.sinh.doc)
.def("cosh", &symbolic::cosh, doc.cosh.doc)
.def("tanh", &symbolic::tanh, doc.tanh.doc)
.def("min", &symbolic::min, doc.min.doc)
.def("max", &symbolic::max, doc.max.doc)
.def("ceil", &symbolic::ceil, doc.ceil.doc)
.def("__ceil__", &symbolic::ceil, doc.ceil.doc)
.def("floor", &symbolic::floor, doc.floor.doc)
.def("__floor__", &symbolic::floor, doc.floor.doc);
}

void BindSymbolicMathModuleOverloads(py::module m) {
using symbolic::Expression;
BindSymbolicMathOverloads<Expression>(&m);
m // BR
// TODO(eric.cousineau): This is not a NumPy-overridable method using
// dtype=object. Deprecate and move solely into `pydrake.math`.
.def(
"inv",
[](const MatrixX<Expression>& X) -> MatrixX<Expression> {
return X.inverse();
},
"Symbolic matrix inverse");
}

} // namespace internal
Expand Down

0 comments on commit 9356274

Please sign in to comment.