Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#7494 from m-chaturvedi/try_pybind1…
Browse files Browse the repository at this point in the history
…1_change

Use a more recent Pybind11 fork
  • Loading branch information
sherm1 authored Nov 17, 2017
2 parents 008ac3e + 6d72394 commit e00389b
Show file tree
Hide file tree
Showing 12 changed files with 32 additions and 48 deletions.
4 changes: 2 additions & 2 deletions WORKSPACE
Original file line number Diff line number Diff line change
Expand Up @@ -238,8 +238,8 @@ github_archive(
github_archive(
name = "pybind11",
repository = "RobotLocomotion/pybind11",
commit = "6d72785766558047ee2e2075198c07d8c25eb631",
sha256 = "08b4813b3b17f607efc4e8ba8b73bf55759ba744cab125e9fc666b5161cb1d0a", # noqa
commit = "ffcf754ae9e766632610975d22372a86a7b63014",
sha256 = "7cd6f4efb02bf9ae17eeb2afba68023af913e61ae76e8b4254203d0eec019525", # noqa
build_file = "tools/workspace/pybind11/pybind11.BUILD.bazel",
)

Expand Down
6 changes: 2 additions & 4 deletions drake/bindings/pybind11/pydrake_autodiffutils.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@ AutoDiffXd eval(const Eigen::AutoDiffScalar<Derived>& x) {
return AutoDiffXd(x.value(), x.derivatives());
}

PYBIND11_PLUGIN(_pydrake_autodiffutils) {
py::module m("_pydrake_autodiffutils", "Bindings for Eigen AutoDiff Scalars");
PYBIND11_MODULE(_pydrake_autodiffutils, m) {
m.doc() = "Bindings for Eigen AutoDiff Scalars";

py::class_<AutoDiffXd>(m, "AutoDiffXd")
.def("__init__",
Expand Down Expand Up @@ -77,6 +77,4 @@ PYBIND11_PLUGIN(_pydrake_autodiffutils) {
.def("__rtruediv__", [](const AutoDiffXd& self, double other) {
return eval(other / self);
}, py::is_operator());

return m.ptr();
}
6 changes: 2 additions & 4 deletions drake/bindings/pybind11/pydrake_common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@ void trigger_an_assertion_failure() {
}
} // namespace

PYBIND11_PLUGIN(_pydrake_common) {
py::module m("_pydrake_common", "Bindings for //drake/common:common");
PYBIND11_MODULE(_pydrake_common, m) {
m.doc() = "Bindings for //drake/common:common";

// Turn DRAKE_ASSERT and DRAKE_DEMAND exceptions into native SystemExit.
// Admittedly, it's unusual for a python library like pydrake to raise
Expand Down Expand Up @@ -60,6 +60,4 @@ PYBIND11_PLUGIN(_pydrake_common) {
"Set Drake's assertion failure mechanism to be exceptions");
m.def("trigger_an_assertion_failure", &trigger_an_assertion_failure,
"Trigger a Drake C++ assertion failure");

return m.ptr();
}
6 changes: 2 additions & 4 deletions drake/bindings/pybind11/pydrake_gurobi.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,15 @@

namespace py = pybind11;

PYBIND11_PLUGIN(gurobi) {
PYBIND11_MODULE(gurobi, m) {
using drake::solvers::GurobiSolver;

py::module m("gurobi", "Gurobi solver bindings for MathematicalProgram");
m.doc() = "Gurobi solver bindings for MathematicalProgram";

py::object solverinterface =
py::module::import("pydrake.solvers.mathematicalprogram").attr(
"MathematicalProgramSolverInterface");

py::class_<GurobiSolver>(m, "GurobiSolver", solverinterface)
.def(py::init<>());

return m.ptr();
}
6 changes: 2 additions & 4 deletions drake/bindings/pybind11/pydrake_ik.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@

namespace py = pybind11;

PYBIND11_PLUGIN(_pydrake_ik) {
py::module m("_pydrake_ik", "RigidBodyTree inverse kinematics");
PYBIND11_MODULE(_pydrake_ik, m) {
m.doc() = "RigidBodyTree inverse kinematics";

py::class_<RigidBodyConstraint>(m, "RigidBodyConstraint");

Expand Down Expand Up @@ -245,6 +245,4 @@ PYBIND11_PLUGIN(_pydrake_ik) {
.def_readonly("q_sol", &IKResults::q_sol)
.def_readonly("info", &IKResults::info)
.def_readonly("infeasible_constraints", &IKResults::infeasible_constraints);

return m.ptr();
}
6 changes: 2 additions & 4 deletions drake/bindings/pybind11/pydrake_ipopt.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,15 @@

namespace py = pybind11;

PYBIND11_PLUGIN(ipopt) {
PYBIND11_MODULE(ipopt, m) {
using drake::solvers::IpoptSolver;

py::module m("ipopt", "Ipopt solver bindings for MathematicalProgram");
m.doc() = "Ipopt solver bindings for MathematicalProgram";

py::object solverinterface =
py::module::import("pydrake.solvers.mathematicalprogram").attr(
"MathematicalProgramSolverInterface");

py::class_<IpoptSolver>(m, "IpoptSolver", solverinterface)
.def(py::init<>());

return m.ptr();
}
7 changes: 2 additions & 5 deletions drake/bindings/pybind11/pydrake_mathematicalprogram.cc
Original file line number Diff line number Diff line change
Expand Up @@ -78,9 +78,8 @@ auto RegisterBinding(py::handle* pscope,

} // namespace

PYBIND11_PLUGIN(_pydrake_mathematicalprogram) {
py::module m("_pydrake_mathematicalprogram",
"Drake MathematicalProgram Bindings");
PYBIND11_MODULE(_pydrake_mathematicalprogram, m) {
m.doc() = "Drake MathematicalProgram Bindings";

py::object variable =
py::module::import("pydrake.symbolic").attr("Variable");
Expand Down Expand Up @@ -271,6 +270,4 @@ PYBIND11_PLUGIN(_pydrake_mathematicalprogram) {

RegisterBinding<LinearCost>(&m, &prog_cls, "LinearCost");
RegisterBinding<QuadraticCost>(&m, &prog_cls, "QuadraticCost");

return m.ptr();
}
6 changes: 2 additions & 4 deletions drake/bindings/pybind11/pydrake_mosek.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,15 @@

namespace py = pybind11;

PYBIND11_PLUGIN(mosek) {
PYBIND11_MODULE(mosek, m) {
using drake::solvers::MosekSolver;

py::module m("mosek", "Mosek solver bindings for MathematicalProgram");
m.doc() = "Mosek solver bindings for MathematicalProgram";

py::object solverinterface =
py::module::import("pydrake.solvers.mathematicalprogram").attr(
"MathematicalProgramSolverInterface");

py::class_<MosekSolver>(m, "MosekSolver", solverinterface)
.def(py::init<>());

return m.ptr();
}
6 changes: 2 additions & 4 deletions drake/bindings/pybind11/pydrake_parsers.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@

namespace py = pybind11;

PYBIND11_PLUGIN(parsers) {
PYBIND11_MODULE(parsers, m) {
using drake::parsers::PackageMap;

py::module m("parsers", "Tools for loading robots from various files");
m.doc() = "Tools for loading robots from various files";

py::class_<PackageMap>(m, "PackageMap")
.def(py::init<>(), py::return_value_policy::reference)
Expand All @@ -18,6 +18,4 @@ PYBIND11_PLUGIN(parsers) {
.def("PopulateFromFolder", &PackageMap::PopulateFromFolder)
.def("PopulateFromEnvironment", &PackageMap::PopulateFromEnvironment)
.def("PopulateUpstreamToDrake", &PackageMap::PopulateUpstreamToDrake);

return m.ptr();
}
6 changes: 2 additions & 4 deletions drake/bindings/pybind11/pydrake_rbtree.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@

namespace py = pybind11;

PYBIND11_PLUGIN(_pydrake_rbtree) {
py::module m("_pydrake_rbtree", "Bindings for the RigidBodyTree class");
PYBIND11_MODULE(_pydrake_rbtree, m) {
m.doc() = "Bindings for the RigidBodyTree class";

using drake::AutoDiffXd;
using drake::multibody::joints::FloatingBaseType;
Expand Down Expand Up @@ -200,6 +200,4 @@ PYBIND11_PLUGIN(_pydrake_rbtree) {
m.def("AddModelInstanceFromUrdfStringSearchingInRosPackages",
&drake::parsers::urdf::\
AddModelInstanceFromUrdfStringSearchingInRosPackages);

return m.ptr();
}
7 changes: 2 additions & 5 deletions drake/bindings/pybind11/pydrake_symbolic.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,13 @@

namespace py = pybind11;

PYBIND11_PLUGIN(_pydrake_symbolic) {
PYBIND11_MODULE(_pydrake_symbolic, m) {
using drake::symbolic::Variable;
using drake::symbolic::Expression;
using drake::symbolic::Formula;
using drake::symbolic::pow;

py::module m("_pydrake_symbolic",
"Symbolic variables, expressions, and formulae");
m.doc() = "Symbolic variables, expressions, and formulae";

py::class_<Variable>(m, "Variable")
.def(py::init<const std::string&>())
Expand Down Expand Up @@ -248,6 +247,4 @@ PYBIND11_PLUGIN(_pydrake_symbolic) {
.def("logical_not", [](const Formula& a) {
return !a;
});

return m.ptr();
}
14 changes: 10 additions & 4 deletions tools/workspace/pybind11/pybind11.BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -15,22 +15,29 @@ cc_library(
name = "pybind11",
hdrs = [
"include/pybind11/attr.h",
"include/pybind11/buffer_info.h",
"include/pybind11/cast.h",
"include/pybind11/chrono.h",
"include/pybind11/common.h",
"include/pybind11/complex.h",
"include/pybind11/descr.h",
"include/pybind11/detail/class.h",
"include/pybind11/detail/common.h",
"include/pybind11/detail/descr.h",
"include/pybind11/detail/init.h",
"include/pybind11/detail/internals.h",
"include/pybind11/detail/typeid.h",
"include/pybind11/eigen.h",
"include/pybind11/embed.h",
"include/pybind11/eval.h",
"include/pybind11/functional.h",
"include/pybind11/iostream.h",
"include/pybind11/numpy.h",
"include/pybind11/operators.h",
"include/pybind11/options.h",
"include/pybind11/pybind11.h",
"include/pybind11/pytypes.h",
"include/pybind11/stl.h",
"include/pybind11/stl_bind.h",
"include/pybind11/typeid.h",
],
includes = ["include"],
deps = [
Expand All @@ -43,7 +50,7 @@ cc_library(
cmake_config(
package = "pybind11",
script = "@drake//tools/workspace/pybind11:pybind11-create-cps.py",
version_file = "include/pybind11/common.h",
version_file = "include/pybind11/detail/common.h",
)

# Creates rule :install_cmake_config.
Expand All @@ -53,7 +60,6 @@ install_files(
name = "install_extra_cmake",
dest = "lib/cmake/pybind11",
files = [
"tools/FindNumPy.cmake",
"tools/FindPythonLibsNew.cmake",
"tools/pybind11Tools.cmake",
],
Expand Down

0 comments on commit e00389b

Please sign in to comment.