Skip to content

Commit

Permalink
Deprecate ComputeBasisFromAxis() in C++ and Python. (RobotLocomotion#…
Browse files Browse the repository at this point in the history
…15154)

* Deprecate MakeOrthonormalBasis() in C++ and Python.

* Remove the part of the deprecation message that is mostly auto-generated.
  • Loading branch information
mitiguy authored Jun 15, 2021
1 parent 8e0dc4c commit 6c5a106
Show file tree
Hide file tree
Showing 5 changed files with 23 additions and 9 deletions.
1 change: 1 addition & 0 deletions bindings/pydrake/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,7 @@ drake_pybind_library(
"//bindings/pydrake:symbolic_types_pybind",
"//bindings/pydrake/common:cpp_template_pybind",
"//bindings/pydrake/common:default_scalars_pybind",
"//bindings/pydrake/common:deprecation_pybind",
"//bindings/pydrake/common:eigen_pybind",
"//bindings/pydrake/common:type_pack",
"//bindings/pydrake/common:value_pybind",
Expand Down
17 changes: 11 additions & 6 deletions bindings/pydrake/math_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
#include "drake/bindings/pydrake/autodiff_types_pybind.h"
#include "drake/bindings/pydrake/common/cpp_template_pybind.h"
#include "drake/bindings/pydrake/common/default_scalars_pybind.h"
#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/eigen_pybind.h"
#include "drake/bindings/pydrake/common/type_pack.h"
#include "drake/bindings/pydrake/common/value_pybind.h"
Expand Down Expand Up @@ -319,12 +320,16 @@ void DoScalarIndependentDefinitions(py::module m) {
// TODO(eric.cousineau): Bind remaining classes for all available scalar
// types.
using T = double;
m.def(
"ComputeBasisFromAxis",
[](int axis_index, const Vector3<T>& axis) {
return ComputeBasisFromAxis(axis_index, axis);
},
py::arg("axis_index"), py::arg("axis_W"), doc.ComputeBasisFromAxis.doc);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
m.def("ComputeBasisFromAxis",
WrapDeprecated(doc.ComputeBasisFromAxis.doc_deprecated,
[](int axis_index, const Vector3<T>& axis) {
return ComputeBasisFromAxis(axis_index, axis);
}),
py::arg("axis_index"), py::arg("axis_W"),
doc.ComputeBasisFromAxis.doc_deprecated);
#pragma GCC diagnostic pop // pop -Wdeprecated-declarations
py::class_<BarycentricMesh<T>>(m, "BarycentricMesh", doc.BarycentricMesh.doc)
.def(py::init<BarycentricMesh<T>::MeshGrid>(),
doc.BarycentricMesh.ctor.doc)
Expand Down
9 changes: 6 additions & 3 deletions bindings/pydrake/test/math_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
from pydrake.common.value import Value
from pydrake.autodiffutils import AutoDiffXd
from pydrake.symbolic import Expression
from pydrake.common.test_utilities.deprecation import catch_drake_warnings
import pydrake.common.test_utilities.numpy_compare as numpy_compare
from pydrake.common.test_utilities.pickle_compare import assert_pickle

Expand Down Expand Up @@ -399,10 +400,12 @@ def test_wrap_to(self, T):
if T != Expression:
self.assertEqual(value, T(.5))

# TODO(2021-10-01) Remove with completion of deprecation.
def test_orthonormal_basis(self):
R = mut.ComputeBasisFromAxis(axis_index=0, axis_W=[1, 0, 0])
self.assertAlmostEqual(np.linalg.det(R), 1.0)
self.assertTrue(np.allclose(R.dot(R.T), np.eye(3)))
with catch_drake_warnings(expected_count=1):
R = mut.ComputeBasisFromAxis(axis_index=0, axis_W=[1, 0, 0])
self.assertAlmostEqual(np.linalg.det(R), 1.0)
self.assertTrue(np.allclose(R.dot(R.T), np.eye(3)))

def test_random_rotations(self):
g = RandomGenerator()
Expand Down
2 changes: 2 additions & 0 deletions math/orthonormal_basis.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include <limits>

#include "drake/common/drake_deprecated.h"
#include "drake/common/eigen_types.h"

namespace drake {
Expand All @@ -22,6 +23,7 @@ namespace math {
/// @throws std::logic_error if the norm of @p axis_W is within 1e-10 to zero or
/// @p axis_index does not lie in the range [0,2].
template <class T>
DRAKE_DEPRECATED("2021-10-01", "Use RotationMatrix::MakeFromOneVector().")
Matrix3<T> ComputeBasisFromAxis(int axis_index, const Vector3<T>& axis_W) {
// Verify that the correct axis is given.
if (axis_index < 0 || axis_index > 2)
Expand Down
3 changes: 3 additions & 0 deletions math/test/orthonormal_basis_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@ namespace drake {
namespace math {
namespace {

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
// Checks that the axes are set correctly.
void CheckBasisOrthonomality(const Matrix3<double>& R) {
const double tol = 10 * std::numeric_limits<double>::epsilon();
Expand Down Expand Up @@ -59,6 +61,7 @@ GTEST_TEST(ComputeBasisFromAxisTest, RightHandOrthogonal) {
CheckBasis(i, z_axis);
}
}
#pragma GCC diagnostic pop // pop -Wdeprecated-declarations

} // namespace
} // namespace math
Expand Down

0 comments on commit 6c5a106

Please sign in to comment.