Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove deprecated code 2021-04-21 #15050

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 0 additions & 16 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -285,22 +285,6 @@ void DoScalarDependentDefinitions(py::module m, T) {
// TODO(eric.cousineau): Include `CalcInverseDynamics` once there is an
// overload that (a) services MBP directly and (b) uses body
// association that is less awkward than implicit BodyNodeIndex.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
cls // BR
.def("CalcCenterOfMassPosition",
WrapDeprecated(cls_doc.CalcCenterOfMassPosition.doc_deprecated,
overload_cast_explicit<Vector3<T>, const Context<T>&>(
&Class::CalcCenterOfMassPosition)),
py::arg("context"), cls_doc.CalcCenterOfMassPosition.doc_deprecated)
.def("CalcCenterOfMassPosition",
WrapDeprecated(cls_doc.CalcCenterOfMassPosition.doc_deprecated,
overload_cast_explicit<Vector3<T>, const Context<T>&,
const std::vector<ModelInstanceIndex>&>(
&Class::CalcCenterOfMassPosition)),
py::arg("context"), py::arg("model_instances"),
cls_doc.CalcCenterOfMassPosition.doc_deprecated);
#pragma GCC diagnostic pop
cls // BR
.def("CalcTotalMass",
overload_cast_explicit<T, const Context<T>&>(&Class::CalcTotalMass),
Expand Down
7 changes: 0 additions & 7 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -795,13 +795,6 @@ def test_multibody_tree_kinematics(self, T):
context=context, model_instances=[instance])
self.assertTupleEqual(p_com.shape, (3, ))

with catch_drake_warnings(expected_count=2):
p_com = plant.CalcCenterOfMassPosition(context=context)
self.assertTupleEqual(p_com.shape, (3, ))
p_com = plant.CalcCenterOfMassPosition(
context=context, model_instances=[instance])
self.assertTupleEqual(p_com.shape, (3, ))

nq = plant.num_positions()
nv = plant.num_velocities()
wrt_list = [
Expand Down
15 changes: 0 additions & 15 deletions multibody/plant/multibody_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -2479,13 +2479,6 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
return internal_tree().CalcCenterOfMassPositionInWorld(context);
}

DRAKE_DEPRECATED("2021-04-21", "Use CalcCenterOfMassPositionInWorld() "
"instead of CalcCenterOfMassPosition().")
Vector3<T> CalcCenterOfMassPosition(
const systems::Context<T>& context) const {
return CalcCenterOfMassPositionInWorld(context);
}

/// Calculates the position vector from the world origin Wo to the center of
/// mass of all bodies contained in model_instances, expressed in the world
/// frame W.
Expand All @@ -2507,14 +2500,6 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
CalcCenterOfMassPositionInWorld(context, model_instances);
}

DRAKE_DEPRECATED("2021-04-21", "Use CalcCenterOfMassPositionInWorld() "
"instead of CalcCenterOfMassPosition().")
Vector3<T> CalcCenterOfMassPosition(
const systems::Context<T>& context,
const std::vector<ModelInstanceIndex>& model_instances) const {
return CalcCenterOfMassPositionInWorld(context, model_instances);
}

/// Calculates system center of mass translational velocity in world frame W.
/// @param[in] context The context contains the state of the model.
/// @retval v_WScm_W Scm's translational velocity in frame W, expressed in W,
Expand Down
31 changes: 0 additions & 31 deletions multibody/plant/test/multibody_plant_com_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,6 @@ GTEST_TEST(EmptyMultibodyPlantCenterOfMassTest, CalcCenterOfMassPosition) {
"CalcCenterOfMassPositionInWorld\\(\\): This MultibodyPlant contains "
"only the world_body\\(\\) so its center of mass is undefined.");

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
DRAKE_EXPECT_THROWS_MESSAGE(
plant.CalcCenterOfMassPosition(*context_),
std::exception,
"CalcCenterOfMassPositionInWorld\\(\\): This MultibodyPlant contains "
"only the world_body\\(\\) so its center of mass is undefined.");
#pragma GCC diagnostic pop // pop -Wdeprecated-declarations

DRAKE_EXPECT_THROWS_MESSAGE(
plant.CalcCenterOfMassTranslationalVelocityInWorld(*context_),
std::exception,
Expand Down Expand Up @@ -90,14 +81,6 @@ class MultibodyPlantCenterOfMassTest : public ::testing::Test {
// Allow for 3 bits (2^3 = 8) of error.
const double kTolerance = 8 * std::numeric_limits<double>::epsilon();
EXPECT_TRUE(CompareMatrices(p_WCcm, p_WCcm_expected, kTolerance));

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
Eigen::Vector3d p_WCcm_deprecated =
plant_.CalcCenterOfMassPosition(*context_);
EXPECT_TRUE(
CompareMatrices(p_WCcm_deprecated, p_WCcm_expected, kTolerance));
#pragma GCC diagnostic pop // pop -Wdeprecated-declarations
}

const RigidBody<double>& GetSphereBody() {
Expand Down Expand Up @@ -223,13 +206,6 @@ TEST_F(MultibodyPlantCenterOfMassTest, CenterOfMassPosition) {
const double kTolerance = 8 * std::numeric_limits<double>::epsilon();
EXPECT_TRUE(CompareMatrices(p_WCcm, result, kTolerance));

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
Eigen::Vector3d p_WCcm_deprecatedA =
plant_.CalcCenterOfMassPosition(*context_);
EXPECT_TRUE(CompareMatrices(p_WCcm_deprecatedA, result, kTolerance));
#pragma GCC diagnostic pop // pop -Wdeprecated-declarations

// Verify the plant's center of mass location for an arbitrary input.
const Eigen::Vector3d p_WSo_W(1.1, 2.3, 3.7);
const Eigen::Vector3d p_WTo_W(-5.2, 10.4, -6.8);
Expand Down Expand Up @@ -298,13 +274,6 @@ TEST_F(MultibodyPlantCenterOfMassTest, CenterOfMassPosition) {
p_WCcm = plant_.CalcCenterOfMassPositionInWorld(*context_, model_instances);
EXPECT_TRUE(CompareMatrices(p_WCcm, result, kTolerance));

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
Eigen::Vector3d p_WCcm_deprecatedB =
plant_.CalcCenterOfMassPosition(*context_, model_instances);
EXPECT_TRUE(CompareMatrices(p_WCcm_deprecatedB, result, kTolerance));
#pragma GCC diagnostic pop // pop -Wdeprecated-declarations

// Verify CalcCenterOfMassPositionInWorld() works for 2 objects in
// model_instances, where the 2 objects have arbitrary orientation/position.
const math::RigidTransformd X_WS2(math::RollPitchYawd(0.3, -1.5, 0.7),
Expand Down