Skip to content

Commit

Permalink
[common] Remove deprecated code 2022-11 (#18224)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri committed Nov 1, 2022
1 parent dba4613 commit 4c49a52
Show file tree
Hide file tree
Showing 9 changed files with 1 addition and 319 deletions.
107 changes: 0 additions & 107 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,6 @@ load(
"drake_cc_package_library",
"drake_cc_test",
)
load(
"@drake//tools/skylark:alias.bzl",
"drake_cc_hdrs_forwarding_library",
)
load(
"@drake//tools/skylark:drake_py.bzl",
"drake_py_binary",
Expand All @@ -27,7 +23,6 @@ drake_cc_package_library(
visibility = ["//visibility:public"],
deps = [
":autodiff",
":autodiffxd_make_coherent",
":bit_cast",
":cond",
":copyable_unique_ptr",
Expand Down Expand Up @@ -56,11 +51,6 @@ drake_cc_package_library(
":scope_exit",
":scoped_singleton",
":sorted_pair",
":symbolic",
":symbolic_decompose",
":symbolic_forwarding",
":symbolic_latex",
":symbolic_trigonometric_polynomial",
":temp_directory",
":timer",
":type_safe_index",
Expand Down Expand Up @@ -176,15 +166,6 @@ drake_cc_library(
],
)

drake_cc_library(
name = "autodiffxd_make_coherent",
hdrs = ["autodiffxd_make_coherent.h"],
deps = [
":autodiff",
"//common/symbolic:expression",
],
)

drake_cc_library(
name = "polynomial",
srcs = ["polynomial.cc"],
Expand All @@ -197,73 +178,6 @@ drake_cc_library(
],
)

# Remove this deprecataion shim on or after 2022-11-01.
drake_cc_library(
name = "symbolic",
hdrs = ["symbolic.h"],
deps = [":symbolic_forwarding"],
)

# Remove this deprecataion shim on or after 2022-11-01.
drake_cc_hdrs_forwarding_library(
name = "symbolic_forwarding",
actual_subdir = "common/symbolic",
add_deprecation_warning = True,
relative_labels_map = {
":symbolic_chebyshev_basis_element": ":chebyshev_basis_element",
":symbolic_chebyshev_polynomial": ":chebyshev_polynomial",
":symbolic_codegen": ":codegen",
":symbolic_decompose": ":decompose",
":symbolic_generic_polynomial": ":generic_polynomial",
":symbolic_monomial": ":monomial",
":symbolic_monomial_basis_element": ":monomial_basis_element",
":symbolic_monomial_util": ":monomial_util",
":symbolic_polynomial": ":polynomial",
":symbolic_polynomial_basis": ":polynomial_basis",
":symbolic_polynomial_basis_element": ":polynomial_basis_element",
":symbolic_rational_function": ":rational_function",
":symbolic_simplification": ":simplification",
},
visibility = ["//visibility:private"],
deps = [
"//common/symbolic",
],
)

# Remove this deprecataion shim on or after 2022-11-01.
drake_cc_library(
name = "symbolic_decompose",
deps = [
":symbolic",
],
)

# Remove this deprecataion shim on or after 2022-11-01.
drake_cc_hdrs_forwarding_library(
name = "symbolic_latex",
actual_subdir = "common/symbolic",
add_deprecation_warning = True,
relative_labels_map = {
":symbolic_latex": ":latex",
},
deps = [
"//common/symbolic:latex",
],
)

# Remove this deprecataion shim on or after 2022-11-01.
drake_cc_hdrs_forwarding_library(
name = "symbolic_trigonometric_polynomial",
actual_subdir = "common/symbolic",
add_deprecation_warning = True,
relative_labels_map = {
":symbolic_trigonometric_polynomial": ":trigonometric_polynomial",
},
deps = [
"//common/symbolic:trigonometric_polynomial",
],
)

drake_cc_library(
name = "default_scalars",
hdrs = ["default_scalars.h"],
Expand Down Expand Up @@ -664,17 +578,6 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "deprecated_symbolic_headers_test",
copts = ["-Wno-cpp"],
deps = [
":symbolic",
":symbolic_decompose",
":symbolic_latex",
":symbolic_trigonometric_polynomial",
],
)

drake_cc_googletest(
name = "drake_bool_test",
deps = [
Expand Down Expand Up @@ -990,16 +893,6 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "autodiffxd_make_coherent_test",
copts = ["-Wno-deprecated-declarations"],
deps = [
":autodiffxd_make_coherent",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:expect_no_throw",
],
)

drake_cc_googletest(
name = "never_destroyed_test",
deps = [
Expand Down
40 changes: 0 additions & 40 deletions common/autodiffxd_make_coherent.h

This file was deleted.

22 changes: 0 additions & 22 deletions common/symbolic.h

This file was deleted.

47 changes: 0 additions & 47 deletions common/symbolic/decompose.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
#include <unordered_map>
#include <utility>

#include "drake/common/drake_deprecated.h"
#include "drake/common/eigen_types.h"
#include "drake/common/symbolic/expression.h"
#include "drake/common/symbolic/polynomial.h"
Expand Down Expand Up @@ -135,52 +134,6 @@ int DecomposeAffineExpression(
const std::unordered_map<symbolic::Variable::Id, int>& map_var_to_index,
EigenPtr<Eigen::RowVectorXd> coeffs, double* constant_term);

/** Decomposes an affine combination @p e = c0 + c1 * v1 + ... cn * vn into the
following:
constant term : c0
coefficient vector : [c1, ..., cn]
variable vector : [v1, ..., vn]
Then, it extracts the coefficient and the constant term. A map from variable ID
to int, @p map_var_to_index, is used to decide a variable's index in a linear
combination.
\pre
1. @c coeffs is a row vector of double, whose length matches with the size of
@c map_var_to_index.
2. e.is_polynomial() is true.
3. e is an affine expression.
@tparam Derived An Eigen row vector type with Derived::Scalar == double.
@param[in] e The symbolic affine expression
@param[in] map_var_to_index A mapping from variable ID to variable index, such
that map_var_to_index[vi.get_ID()] = i.
@param[out] coeffs A row vector. coeffs(i) = ci.
@param[out] constant_term c0 in the equation above.
@return num_variable. Number of variables in the expression. 2 * x(0) + 3 has 1
variable, 2 * x(0) + 3 * x(1) - 2 * x(0) has 1 variable. */
template <typename Derived>
DRAKE_DEPRECATED("2022-11-01",
"Use the overloaded DecomposeAffineExpression which takes "
"coeffs as a pointer.")
typename std::enable_if_t<
std::is_same_v<typename Derived::Scalar, double>,
int> DecomposeAffineExpression(const symbolic::Expression& e,
const std::unordered_map<
symbolic::Variable::Id, int>&
map_var_to_index,
const Eigen::MatrixBase<Derived>& coeffs,
double* constant_term) {
Eigen::MatrixBase<Derived>& coeffs_ref =
const_cast<Eigen::MatrixBase<Derived>&>(coeffs);
Eigen::RowVectorXd coeffs_row(coeffs.cols());
const int num_vars = DecomposeAffineExpression(e, map_var_to_index,
&coeffs_row, constant_term);
coeffs_ref = coeffs_row;
return num_vars;
}

/** Given a vector of Expressions @p f and a list of @p parameters we define
all additional variables in @p f to be a vector of "non-parameter variables",
n. This method returns a factorization of @p f into an equivalent "data
Expand Down
12 changes: 0 additions & 12 deletions common/symbolic/test/decompose_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -349,18 +349,6 @@ GTEST_TEST(SymbolicExtraction, DecomposeAffineExpression) {
EXPECT_TRUE(CompareMatrices(coeffs_expected, coeffs, kEps));
EXPECT_EQ(c_expected, c);

// TODO(hongkai.dai): 2022-11-01 remove the following test after deprecating
// DecomposeAffineExpression with coeffs as a const reference argument.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
Eigen::RowVectorXd coeffs_deprecated(num_variables);
double c_deprecated;
DecomposeAffineExpression(e, map_var_to_index, coeffs_deprecated,
&c_deprecated);
EXPECT_TRUE(CompareMatrices(coeffs_expected, coeffs_deprecated, kEps));
EXPECT_EQ(c_expected, c_deprecated);
#pragma GCC diagnostic pop

// Now test a new expression with different coefficients and we pass in the
// same variable `coeffs`. This tests whether DecomposeAffineExpression
// reset coeffs (when the input coeffs stores some value).
Expand Down
3 changes: 0 additions & 3 deletions common/symbolic_latex.h

This file was deleted.

44 changes: 0 additions & 44 deletions common/test/autodiffxd_make_coherent_test.cc

This file was deleted.

44 changes: 0 additions & 44 deletions common/test/deprecated_symbolic_headers_test.cc

This file was deleted.

0 comments on commit 4c49a52

Please sign in to comment.