Skip to content

Commit

Permalink
trajectories: Remove deprecated methods 2020-07-01 (RobotLocomotion#1…
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Jul 1, 2020
1 parent 5f2d256 commit 695f242
Show file tree
Hide file tree
Showing 12 changed files with 0 additions and 306 deletions.
53 changes: 0 additions & 53 deletions bindings/pydrake/trajectories_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include "pybind11/pybind11.h"
#include "pybind11/stl.h"

#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/polynomial_types_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
Expand Down Expand Up @@ -86,19 +85,6 @@ PYBIND11_MODULE(trajectories, m) {
py::arg("breaks"), py::arg("samples"),
py::arg("zero_end_point_derivatives") = false,
doc.PiecewisePolynomial.CubicShapePreserving.doc)
.def_static(
"Pchip",
[](const Eigen::Ref<const Eigen::VectorXd>& breaks,
const Eigen::Ref<const MatrixX<T>>& samples,
bool zero_end_point_derivatives) {
WarnDeprecated(
"Pchip has been renamed to CubicShapePreserving. "
"Support will be removed after 2020-07-01.");
return PiecewisePolynomial<T>::CubicShapePreserving(
breaks, samples, zero_end_point_derivatives);
},
py::arg("breaks"), py::arg("knots"),
py::arg("zero_end_point_derivatives") = false)
.def_static("CubicWithContinuousSecondDerivatives",
py::overload_cast<const Eigen::Ref<const Eigen::VectorXd>&,
const Eigen::Ref<const MatrixX<T>>&,
Expand All @@ -109,59 +95,20 @@ PYBIND11_MODULE(trajectories, m) {
py::arg("sample_dot_at_end"),
doc.PiecewisePolynomial.CubicWithContinuousSecondDerivatives
.doc_4args)
.def_static(
"Cubic",
[](const Eigen::Ref<const Eigen::VectorXd>& breaks,
const Eigen::Ref<const MatrixX<T>>& samples,
const Eigen::Ref<const VectorX<T>>& sample_dot_at_start,
const Eigen::Ref<const VectorX<T>>& sample_dot_at_end) {
WarnDeprecated(
"This version of Cubic has been renamed to "
"CubicWithContinuousSecondDerivatives. "
"Support will be removed after 2020-07-01.");
return PiecewisePolynomial<T>::CubicWithContinuousSecondDerivatives(
breaks, samples, sample_dot_at_start, sample_dot_at_end);
},
py::arg("breaks"), py::arg("knots"), py::arg("knots_dot_start"),
py::arg("knots_dot_end"))
.def_static("CubicHermite",
py::overload_cast<const Eigen::Ref<const Eigen::VectorXd>&,
const Eigen::Ref<const MatrixX<T>>&,
const Eigen::Ref<const MatrixX<T>>&>(
&PiecewisePolynomial<T>::CubicHermite),
py::arg("breaks"), py::arg("samples"), py::arg("samples_dot"),
doc.PiecewisePolynomial.CubicHermite.doc)
.def_static(
"Cubic",
[](const Eigen::Ref<const Eigen::VectorXd>& breaks,
const Eigen::Ref<const MatrixX<T>>& samples,
const Eigen::Ref<const MatrixX<T>>& samples_dot) {
WarnDeprecated(
"This version of Cubic has been renamed to CubicHermite. "
"Support will be removed after 2020-07-01.");
return PiecewisePolynomial<T>::CubicHermite(
breaks, samples, samples_dot);
},
py::arg("breaks"), py::arg("knots"), py::arg("knots_dot"))
.def_static("CubicWithContinuousSecondDerivatives",
py::overload_cast<const Eigen::Ref<const Eigen::VectorXd>&,
const Eigen::Ref<const MatrixX<T>>&, bool>(
&PiecewisePolynomial<T>::CubicWithContinuousSecondDerivatives),
py::arg("breaks"), py::arg("samples"), py::arg("periodic_end"),
doc.PiecewisePolynomial.CubicWithContinuousSecondDerivatives
.doc_3args)
.def_static(
"Cubic",
[](const Eigen::Ref<const Eigen::VectorXd>& breaks,
const Eigen::Ref<const MatrixX<T>>& samples, bool periodic_end) {
WarnDeprecated(
"This version of Cubic has been renamed to "
"CubicWithContinuousSecondDerivatives. "
"Support will be removed after 2020-07-01.");
return PiecewisePolynomial<T>::CubicWithContinuousSecondDerivatives(
breaks, samples, periodic_end);
},
py::arg("breaks"), py::arg("knots"), py::arg("periodic_end"))
.def_static("LagrangeInterpolatingPolynomial",
py::overload_cast<const Eigen::Ref<const Eigen::VectorXd>&,
const Eigen::Ref<const MatrixX<T>>&>(
Expand Down
32 changes: 0 additions & 32 deletions common/polynomial.h
Original file line number Diff line number Diff line change
Expand Up @@ -517,20 +517,6 @@ std::ostream& operator<<(
return os;
}

#ifndef DRAKE_DOXYGEN_CXX
namespace symbolic {
namespace internal {
// Helper to implement (deprecated) Expression::ToPolynomial.
// TODO(soonho-tri): Remove this on or after 2020-07-01 when we remove
// Expression::ToPolynomial.
inline drake::Polynomial<double> ToPolynomial(
const drake::symbolic::Expression& e, const ToPolynomialHelperTag&) {
return drake::Polynomial<double>::FromExpression(e);
}
} // namespace internal
} // namespace symbolic
#endif

typedef Polynomial<double> Polynomiald;

/// A column vector of polynomials; used in several optimization classes.
Expand All @@ -539,21 +525,3 @@ typedef Eigen::Matrix<Polynomiald, Eigen::Dynamic, 1> VectorXPoly;

DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
class drake::Polynomial)

/** Provides power function for Polynomial. */
template <typename T>
DRAKE_DEPRECATED("2020-07-01", "Use drake::pow instead.")
drake::Polynomial<T> pow(const drake::Polynomial<T>& base,
typename drake::Polynomial<T>::PowerType exponent) {
return drake::pow(base, exponent);
}

template <typename T = double>
using Polynomial DRAKE_DEPRECATED(
"2020-07-01", "Use drake::Polynomial instead.") = drake::Polynomial<T>;

using Polynomiald DRAKE_DEPRECATED("2020-07-01", "Use drake::Polynomiald.") =
drake::Polynomial<double>;

using VectorXPoly DRAKE_DEPRECATED("2020-07-01", "Use drake::VectorXPoly.") =
Eigen::Matrix<drake::Polynomiald, Eigen::Dynamic, 1>;
26 changes: 0 additions & 26 deletions common/symbolic_expression.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
#include "drake/common/cond.h"
#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/drake_deprecated.h"
#include "drake/common/drake_throw.h"
#include "drake/common/dummy_value.h"
#include "drake/common/eigen_types.h"
Expand All @@ -38,20 +37,6 @@ namespace drake {

namespace symbolic {

#ifndef DRAKE_DOXYGEN_CXX
class Expression;
namespace internal {
// Helper to implement (deprecated) Expression::ToPolynomial.
// TODO(soonho-tri): Remove this on or after 2020-07-01 when we remove
// Expression::ToPolynomial.
struct ToPolynomialHelperTag {};
template <typename Dummy>
auto ToPolynomialHelper(const Expression& e, const Dummy&) {
return ToPolynomial(e, Dummy{});
}
} // namespace internal
#endif

/** Kinds of symbolic expressions. */
enum class ExpressionKind {
Constant, ///< constant (double)
Expand Down Expand Up @@ -244,17 +229,6 @@ class Expression {
/** Checks if this symbolic expression is convertible to Polynomial. */
bool is_polynomial() const;

/** Returns a Polynomial representing this expression.
* Note that the ID of a variable is preserved in this translation.
* \pre{is_polynomial() is true.}
*/
template <typename Dummy = internal::ToPolynomialHelperTag>
DRAKE_DEPRECATED("2020-07-01",
"Use drake::ToPolynomial(const Expression&) instead.")
auto ToPolynomial() const {
return internal::ToPolynomialHelper<Dummy>(*this, Dummy{});
}

/** Evaluates using a given environment (by default, an empty environment) and
* a random number generator. If there is a random variable in this expression
* which is unassigned in @p env, this method uses @p random_generator to
Expand Down
18 changes: 0 additions & 18 deletions common/test/polynomial_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -511,24 +511,6 @@ GTEST_TEST(PolynomialTest, FromExpression) {
}
}

// Checks deprecated aliases.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"

// TODO(soonho-tri): Remove the following checks when we remove ::Polynomial.
static_assert(
std::is_same<::Polynomial<double>, drake::Polynomial<double>>::value,
"::Polynomial should be an alias of drake::Polynomial.");
static_assert(std::is_same<::Polynomiald, drake::Polynomiald>::value,
"::Polynomiald should be an alias of drake::Polynomiald.");
static_assert(std::is_same<::VectorXPoly, drake::VectorXPoly>::value,
"::VectorXPoly should be an alias of drake::VectorXPoly.");
GTEST_TEST(PolynomialTest, DeprecatedPow) {
const Polynomiald x = Polynomiald("x");
EXPECT_EQ(::pow(x, 2), x * x);
}
#pragma GCC diagnostic pop

template <typename T>
void TestScalarType() {
Eigen::Vector3d coeffs(1., 2., 3.);
Expand Down
55 changes: 0 additions & 55 deletions common/test/symbolic_expression_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -542,61 +542,6 @@ TEST_F(SymbolicExpressionTest, IsPolynomial) {
EXPECT_FALSE(sqrt(pow(x_, 2)).is_polynomial());
}

// TODO(soonho-tri): Remove the following tests on or after 2020-07-01 when we
// remove Expression::ToPolynomial.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
TEST_F(SymbolicExpressionTest, ToPolynomial1) {
Environment env{{var_x_, 1.0}, {var_y_, 2.0}, {var_z_, 3.0}};
const map<Polynomiald::VarType, double> eval_point{
{var_x_.get_id(), env[var_x_]},
{var_y_.get_id(), env[var_y_]},
{var_z_.get_id(), env[var_z_]}};

const Expression e0{42.0};
const Expression e1{pow(x_, 2)};
const Expression e2{3 + x_ + y_ + z_};
const Expression e3{1 + pow(x_, 2) + pow(y_, 2)};
const Expression e4{pow(x_, 2) * pow(y_, 2)};
const Expression e5{pow(x_ + y_ + z_, 3)};
const Expression e6{pow(x_ + y_ + z_, 3) / 10};
const Expression e7{-pow(y_, 3)};
const Expression e8{pow(pow(x_, 3), 1.0 / 3)};

EXPECT_NEAR(e0.Evaluate(env),
e0.ToPolynomial().EvaluateMultivariate(eval_point), 1e-8);
EXPECT_NEAR(e1.Evaluate(env),
e1.ToPolynomial().EvaluateMultivariate(eval_point), 1e-8);
EXPECT_NEAR(e2.Evaluate(env),
e2.ToPolynomial().EvaluateMultivariate(eval_point), 1e-8);
EXPECT_NEAR(e3.Evaluate(env),
e3.ToPolynomial().EvaluateMultivariate(eval_point), 1e-8);
EXPECT_NEAR(e4.Evaluate(env),
e4.ToPolynomial().EvaluateMultivariate(eval_point), 1e-8);
EXPECT_NEAR(e5.Evaluate(env),
e5.ToPolynomial().EvaluateMultivariate(eval_point), 1e-8);
EXPECT_NEAR(e6.Evaluate(env),
e6.ToPolynomial().EvaluateMultivariate(eval_point), 1e-8);
EXPECT_NEAR(e7.Evaluate(env),
e7.ToPolynomial().EvaluateMultivariate(eval_point), 1e-8);
EXPECT_NEAR(e8.Evaluate(env),
e8.ToPolynomial().EvaluateMultivariate(eval_point), 1e-8);
}

TEST_F(SymbolicExpressionTest, ToPolynomial2) {
const vector<Expression> test_vec{
e_log_, e_abs_, e_exp_, e_sqrt_, e_sin_,
e_cos_, e_tan_, e_asin_, e_acos_, e_atan_,
e_atan2_, e_sinh_, e_cosh_, e_tanh_, e_min_,
e_max_, e_ceil_, e_floor_, e_ite_, Expression::NaN(),
e_uf_};
for (const Expression& e : test_vec) {
EXPECT_FALSE(e.is_polynomial());
EXPECT_THROW(e.ToPolynomial(), runtime_error);
}
}
#pragma GCC diagnostic pop

TEST_F(SymbolicExpressionTest, LessKind) {
CheckOrdering({e_constant_, e_var_, e_add_, e_neg_, e_mul_, e_div_,
e_log_, e_abs_, e_exp_, e_sqrt_, e_pow_, e_sin_,
Expand Down
14 changes: 0 additions & 14 deletions common/test/trig_poly_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -133,20 +133,6 @@ GTEST_TEST(TrigPolyTest, EvaluatePartialTest) {
theta + cos(theta) + sin(theta + 1));
}

// Checks deprecated aliases.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"

// TODO(soonho-tri): Remove the following checks when we remove ::TrigPoly.
static_assert(std::is_same<::TrigPoly<double>, drake::TrigPoly<double>>::value,
"::TrigPoly should be an alias of drake::TrigPoly.");
static_assert(std::is_same<::TrigPolyd, drake::TrigPolyd>::value,
"::TrigPolyd should be an alias of drake::TrigPolyd.");
static_assert(
std::is_same<::VectorXTrigPoly, drake::VectorXTrigPoly>::value,
"::VectorXTrigPoly should be an alias of drake::VectorXTrigPoly.");
#pragma GCC diagnostic pop

} // anonymous namespace
} // namespace util
} // namespace drake
Loading

0 comments on commit 695f242

Please sign in to comment.