Skip to content

Commit

Permalink
py eigen: Expose default scalars
Browse files Browse the repository at this point in the history
  • Loading branch information
EricCousineau-TRI committed May 8, 2019
1 parent 13e61c7 commit fc331ee
Show file tree
Hide file tree
Showing 3 changed files with 202 additions and 141 deletions.
11 changes: 10 additions & 1 deletion bindings/pydrake/common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -156,11 +156,19 @@ drake_cc_library(

drake_pybind_library(
name = "eigen_geometry_py",
cc_deps = [":eigen_geometry_pybind"],
cc_deps = [
":cpp_template_pybind",
":default_scalars_pybind",
":eigen_geometry_pybind",
":type_pack",
],
cc_srcs = ["eigen_geometry_py.cc"],
package_info = PACKAGE_INFO,
py_deps = [
":module_py",
":cpp_template_py",
"//bindings/pydrake:autodiffutils_py",
"//bindings/pydrake:symbolic_py",
],
)

Expand Down Expand Up @@ -433,6 +441,7 @@ drake_py_unittest(
deps = [
":eigen_geometry_py",
":eigen_geometry_test_util_py",
"//bindings/pydrake/common/test_utilities:numpy_compare_py",
],
)

Expand Down
67 changes: 48 additions & 19 deletions bindings/pydrake/common/eigen_geometry_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,25 +3,32 @@

#include "pybind11/pybind11.h"

#include "drake/bindings/pydrake/common/cpp_template_pybind.h"
#ifndef __clang__
// N.B. Without this, GCC 7.4.0 on Ubuntu complains about
// `AutoDiffScalar(const AutoDiffScalar& other)` having uninitialized values.
// TODO(eric.cousineau): Figure out why?
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
#include "drake/bindings/pydrake/common/default_scalars_pybind.h"
#pragma GCC diagnostic pop
#else
#include "drake/bindings/pydrake/common/default_scalars_pybind.h"
#endif // __clang__
#include "drake/bindings/pydrake/common/eigen_geometry_pybind.h"
#include "drake/bindings/pydrake/common/type_pack.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
#include "drake/common/drake_assertion_error.h"
#include "drake/common/drake_throw.h"
#include "drake/common/eigen_types.h"

using std::fabs;

namespace drake {
namespace pydrake {
namespace {

// TODO(eric.cousineau): Do not require only SE(3) for isometries because this
// makes it a misnomer: SE(3) ⊂ Isometry(3) b/c Isometry admits reflection.
// Additionally, do not validate for Quaternion, b/c it will break parity with
// C++ and cause odd edge cases when attempting to do projections from non-unit
// quaternions to unit quaternions (e.g. for use with `RigidTransform`).
using std::abs;

// TODO(eric.cousineau): Disable tolerance checks for the symbolic case.
// TODO(eric.cousineau): Remove checks (see #8960).

// N.B. This could potentially interfere with another library's bindings of
// Eigen types. If/when this happens, this should be addressed for both double
Expand All @@ -31,6 +38,8 @@ namespace {
// C++.
const double kCheckTolerance = 1e-5;

using symbolic::Expression;

template <typename T>
void CheckRotMat(const Matrix3<T>& R) {
// See `ExpectRotMat`.
Expand All @@ -39,7 +48,7 @@ void CheckRotMat(const Matrix3<T>& R) {
if (identity_error >= kCheckTolerance) {
throw std::logic_error("Rotation matrix is not orthonormal");
}
const T det_error = fabs(R.determinant() - 1);
const T det_error = abs(R.determinant() - 1);
if (det_error >= kCheckTolerance) {
throw std::logic_error("Rotation matrix violates right-hand rule");
}
Expand All @@ -59,35 +68,46 @@ void CheckSe3(const Isometry3<T>& X) {

template <typename T>
void CheckQuaternion(const Eigen::Quaternion<T>& q) {
const T norm_error = fabs(q.coeffs().norm() - 1);
const T norm_error = abs(q.coeffs().norm() - 1);
if (norm_error >= kCheckTolerance) {
throw std::logic_error("Quaternion is not normalized");
}
}

template <typename T>
void CheckAngleAxis(const Eigen::AngleAxis<T>& value) {
const T norm_error = fabs(value.axis().norm() - 1);
const T norm_error = abs(value.axis().norm() - 1);
if (norm_error >= kCheckTolerance) {
throw std::logic_error("Axis is not normalized");
}
}

} // namespace
// N.B. The following overloads are meant to disable symbolic checks, which are
// not easily achievable for non-numeric values. These can be removed once the
// checks are removed in their entirety (#8960).

PYBIND11_MODULE(eigen_geometry, m) {
m.doc() = "Bindings for Eigen geometric types.";
void CheckRotMat(const Matrix3<Expression>&) {}

void CheckSe3(const Isometry3<Expression>&) {}

void CheckQuaternion(const Eigen::Quaternion<Expression>&) {}

void CheckAngleAxis(const Eigen::AngleAxis<Expression>&) {}

using T = double;
} // namespace

template <typename T>
void DoDefinitions(py::module m, T) {
// Do not return references to matrices (e.g. `Eigen::Ref<>`) so that we have
// tighter control over validation.

py::tuple param = GetPyParam<T>();

// Isometry3d.
// @note `linear` implies rotation, and `affine` implies translation.
{
using Class = Isometry3<T>;
py::class_<Class> cls(m, "Isometry3",
auto cls = DefineTemplateClassWithDefault<Class>(m, "Isometry3", param,
"Provides bindings of Eigen::Isometry3<> that only admit SE(3) "
"(no reflections).");
cls // BR
Expand Down Expand Up @@ -174,7 +194,7 @@ PYBIND11_MODULE(eigen_geometry, m) {
// TODO(eric.cousineau): Should this not be restricted to a unit quaternion?
{
using Class = Eigen::Quaternion<T>;
py::class_<Class> cls(m, "Quaternion",
auto cls = DefineTemplateClassWithDefault<Class>(m, "Quaternion", param,
"Provides a unit quaternion binding of Eigen::Quaternion<>.");
py::object py_class_obj = cls;
cls // BR
Expand Down Expand Up @@ -207,7 +227,7 @@ PYBIND11_MODULE(eigen_geometry, m) {
.def("x", [](const Class* self) { return self->x(); })
.def("y", [](const Class* self) { return self->y(); })
.def("z", [](const Class* self) { return self->z(); })
.def("xyz", [](const Class* self) { return self->vec(); })
.def("xyz", [](const Class* self) { return Vector3<T>(self->vec()); })
.def("wxyz",
[](Class* self) {
Vector4<T> wxyz;
Expand Down Expand Up @@ -260,7 +280,8 @@ PYBIND11_MODULE(eigen_geometry, m) {
// Angle-axis.
{
using Class = Eigen::AngleAxis<T>;
py::class_<Class> cls(m, "AngleAxis", "Bindings for Eigen::AngleAxis<>.");
auto cls = DefineTemplateClassWithDefault<Class>(
m, "AngleAxis", param, "Bindings for Eigen::AngleAxis<>.");
py::object py_class_obj = cls;
cls // BR
.def(py::init([]() { return Class::Identity(); }))
Expand Down Expand Up @@ -335,5 +356,13 @@ PYBIND11_MODULE(eigen_geometry, m) {
}
}

PYBIND11_MODULE(eigen_geometry, m) {
m.doc() = "Bindings for Eigen geometric types.";

py::module::import("pydrake.autodiffutils");
py::module::import("pydrake.symbolic");
type_visit([m](auto dummy) { DoDefinitions(m, dummy); }, CommonScalarPack{});
}

} // namespace pydrake
} // namespace drake
Loading

0 comments on commit fc331ee

Please sign in to comment.