Skip to content

Commit

Permalink
Deprecates default ctor with no arguments. Argument time_step is now …
Browse files Browse the repository at this point in the history
…required. (RobotLocomotion#12525)
  • Loading branch information
amcastro-tri authored Jan 4, 2020
1 parent 2bc3a90 commit bc83ee2
Show file tree
Hide file tree
Showing 43 changed files with 168 additions and 111 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ def main():

# Assemble the Pendulum plant.
builder = DiagramBuilder()
pendulum = builder.AddSystem(MultibodyPlant())
pendulum = builder.AddSystem(MultibodyPlant(0.0))
file_name = FindResourceOrThrow(
"drake/examples/pendulum/Pendulum.urdf")
Parser(pendulum).AddModelFromFile(file_name)
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/manipulation/test/planner_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ def test_api(self):
def test_mbp_overloads(self):
file_name = FindResourceOrThrow(
"drake/multibody/benchmarks/acrobot/acrobot.sdf")
plant = MultibodyPlant()
plant = MultibodyPlant(0.0)
Parser(plant).AddModelFromFile(file_name)
plant.Finalize()

Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/manipulation/test/simple_ui_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ def test_joint_slider(self):
# Simply test to make sure that the UI loads and produces the output.
file_name = FindResourceOrThrow(
"drake/multibody/benchmarks/acrobot/acrobot.sdf")
plant = MultibodyPlant()
plant = MultibodyPlant(0.0)
Parser(plant).AddModelFromFile(file_name)
plant.Finalize()

Expand Down
7 changes: 6 additions & 1 deletion bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,13 @@ void DoScalarDependentDefinitions(py::module m, T) {
m, "MultibodyPlant", param, cls_doc.doc);
// N.B. These are defined as they appear in the class declaration.
// Forwarded methods from `MultibodyTree`.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
cls.def(py_init_deprecated<Class>(cls_doc.ctor.doc_deprecated),
cls_doc.ctor.doc_deprecated);
#pragma GCC diagnostic pop
cls // BR
.def(py::init<double>(), py::arg("time_step") = 0.)
.def(py::init<double>(), py::arg("time_step"), cls_doc.ctor.doc)
.def("num_bodies", &Class::num_bodies, cls_doc.num_bodies.doc)
.def("num_joints", &Class::num_joints, cls_doc.num_joints.doc)
.def("num_actuators", &Class::num_actuators, cls_doc.num_actuators.doc)
Expand Down
29 changes: 17 additions & 12 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import unittest

import numpy as np
import warnings

from pydrake.autodiffutils import AutoDiffXd
from pydrake.symbolic import Expression
Expand Down Expand Up @@ -136,6 +137,10 @@ def assert_sane(self, x, nonzero=True):
if nonzero:
numpy_compare.assert_float_not_equal(x, 0.)

def test_deprecated_zero_argument_constructor(self):
with catch_drake_warnings(expected_count=1):
MultibodyPlant_[float]()

@numpy_compare.check_nonsymbolic_types
def test_multibody_plant_construction_api(self, T):
# SceneGraph does not support `Expression` type.
Expand Down Expand Up @@ -369,7 +374,7 @@ def test_multibody_force_element(self, T):
RevoluteSpring = RevoluteSpring_[T]
SpatialInertia = SpatialInertia_[float]

plant = MultibodyPlant()
plant = MultibodyPlant(0.0)
spatial_inertia = SpatialInertia()
body_a = plant.AddRigidBody(name="body_a",
M_BBo_B=spatial_inertia)
Expand Down Expand Up @@ -405,15 +410,15 @@ def test_multibody_force_element(self, T):
def test_multibody_gravity_default(self, T):
MultibodyPlant = MultibodyPlant_[T]
UniformGravityFieldElement = UniformGravityFieldElement_[T]
plant = MultibodyPlant()
plant = MultibodyPlant(0.0)
with self.assertRaises(RuntimeError) as cm:
plant.AddForceElement(UniformGravityFieldElement())

@numpy_compare.check_all_types
def test_multibody_tree_kinematics(self, T):
RigidTransform = RigidTransform_[T]
SpatialVelocity = SpatialVelocity_[T]
plant_f = MultibodyPlant_[float]()
plant_f = MultibodyPlant_[float](0.0)

file_name = FindResourceOrThrow(
"drake/examples/double_pendulum/models/double_pendulum.sdf")
Expand Down Expand Up @@ -498,7 +503,7 @@ def test_multibody_tree_kinematics(self, T):
def test_multibody_state_access(self, T):
MultibodyPlant = MultibodyPlant_[T]

plant_f = MultibodyPlant_[float]()
plant_f = MultibodyPlant_[float](0.0)
file_name = FindResourceOrThrow(
"drake/multibody/benchmarks/acrobot/acrobot.sdf")
# N.B. `Parser` only supports `MultibodyPlant_[float]`.
Expand Down Expand Up @@ -586,7 +591,7 @@ def test_model_instance_port_access(self, T):
MultibodyPlant = MultibodyPlant_[T]
InputPort = InputPort_[T]
OutputPort = OutputPort_[T]
plant_f = MultibodyPlant_[float]()
plant_f = MultibodyPlant_[float](0.0)
# Create a MultibodyPlant with a kuka arm and a schunk gripper.
# the arm is welded to the world, the gripper is welded to the
# arm's end effector.
Expand Down Expand Up @@ -671,7 +676,7 @@ def check_applied_force_input_ports(self, T):

builder_f = DiagramBuilder_[float]()
# N.B. `Parser` only supports `MultibodyPlant_[float]`.
plant_f = builder_f.AddSystem(MultibodyPlant_[float]())
plant_f = builder_f.AddSystem(MultibodyPlant_[float](0.0))
file_name = FindResourceOrThrow(
"drake/multibody/benchmarks/free_body/uniform_solid_cylinder.urdf")
Parser(plant_f).AddModelFromFile(file_name)
Expand Down Expand Up @@ -721,7 +726,7 @@ def test_model_instance_state_access(self, T):
"iiwa_description/sdf/iiwa14_no_collision.sdf")

# N.B. `Parser` only supports `MultibodyPlant_[float]`.
plant_f = MultibodyPlant_[float]()
plant_f = MultibodyPlant_[float](0.0)
parser = Parser(plant_f)

iiwa_model = parser.AddModelFromFile(
Expand Down Expand Up @@ -974,7 +979,7 @@ def test_map_qdot_to_v_and_back(self, T):
RigidTransform = RigidTransform_[T]
RollPitchYaw = RollPitchYaw_[T]
# N.B. `Parser` only supports `MultibodyPlant_[float]`.
plant_f = MultibodyPlant_[float]()
plant_f = MultibodyPlant_[float](0.0)
iiwa_sdf_path = FindResourceOrThrow(
"drake/manipulation/models/"
"iiwa_description/sdf/iiwa14_no_collision.sdf")
Expand Down Expand Up @@ -1017,7 +1022,7 @@ def test_multibody_add_joint(self, T):
# Python.
num_joints = 2
# N.B. `Parser` only supports `MultibodyPlant_[float]`.
plant_f = MultibodyPlant_[float]()
plant_f = MultibodyPlant_[float](0.0)
parser = Parser(plant_f)
instances = []
for i in range(num_joints + 1):
Expand Down Expand Up @@ -1063,7 +1068,7 @@ def test_multibody_add_frame(self, T):

Frame = Frame_[T]

plant = MultibodyPlant()
plant = MultibodyPlant(0.0)
frame = plant.AddFrame(frame=FixedOffsetFrame(
name="frame", P=plant.world_frame(),
X_PF=RigidTransform_[float].Identity(), model_instance=None))
Expand All @@ -1081,7 +1086,7 @@ def test_multibody_dynamics(self, T):
file_name = FindResourceOrThrow(
"drake/multibody/benchmarks/acrobot/acrobot.sdf")
# N.B. `Parser` only supports `MultibodyPlant_[float]`.
plant_f = MultibodyPlant_[float]()
plant_f = MultibodyPlant_[float](0.0)
Parser(plant_f).AddModelFromFile(file_name)
# Getting ready for when we set foot on Mars :-).
gravity_vector = np.array([0.0, 0.0, -3.71])
Expand Down Expand Up @@ -1192,7 +1197,7 @@ def test_contact_results_to_lcm(self):
# ContactResultsToLcmSystem
file_name = FindResourceOrThrow(
"drake/multibody/benchmarks/acrobot/acrobot.sdf")
plant = MultibodyPlant_[float]()
plant = MultibodyPlant_[float](0.0)
Parser(plant).AddModelFromFile(file_name)
plant.Finalize()
contact_results_to_lcm = ContactResultsToLcmSystem(plant)
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/systems/drawing_graphviz_example.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
"drake/examples/multibody/cart_pole/cart_pole.sdf")
builder = DiagramBuilder()
scene_graph = builder.AddSystem(SceneGraph())
cart_pole = builder.AddSystem(MultibodyPlant())
cart_pole = builder.AddSystem(MultibodyPlant(0.0))
cart_pole.RegisterAsSourceForSceneGraph(scene_graph)
Parser(plant=cart_pole).AddModelFromFile(file_name)

Expand Down
2 changes: 1 addition & 1 deletion examples/kinova_jaco_arm/move_jaco_ee.cc
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ class MoveDemoRunner {

::lcm::LCM lcm_;
std::string urdf_;
MultibodyPlant<double> plant_;
MultibodyPlant<double> plant_{0.0};
multibody::ModelInstanceIndex instance_;
std::unique_ptr<systems::Context<double>> context_;
int status_count_{0};
Expand Down
7 changes: 5 additions & 2 deletions examples/manipulation_station/manipulation_station.cc
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ namespace internal {
SpatialInertia<double> MakeCompositeGripperInertia(
const std::string& wsg_sdf_path,
const std::string& gripper_body_frame_name) {
MultibodyPlant<double> plant;
MultibodyPlant<double> plant(0.0);
multibody::Parser parser(&plant);
parser.AddModelFromFile(wsg_sdf_path);
plant.Finalize();
Expand Down Expand Up @@ -156,7 +156,10 @@ template <typename T>
ManipulationStation<T>::ManipulationStation(double time_step)
: owned_plant_(std::make_unique<MultibodyPlant<T>>(time_step)),
owned_scene_graph_(std::make_unique<SceneGraph<T>>()),
owned_controller_plant_(std::make_unique<MultibodyPlant<T>>()) {
// Given the controller does not compute accelerations, it is irrelevant
// whether the plant is continuous or discrete. We arbitrarily make it
// continuous.
owned_controller_plant_(std::make_unique<MultibodyPlant<T>>(0.0)) {
// This class holds the unique_ptrs explicitly for plant and scene_graph
// until Finalize() is called (when they are moved into the Diagram). Grab
// the raw pointers, which should stay valid for the lifetime of the Diagram.
Expand Down
2 changes: 1 addition & 1 deletion examples/multibody/acrobot/run_lqr.cc
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ std::unique_ptr<systems::AffineSystem<double>> MakeBalancingLQRController(
// Therefore we create a new model that meets this requirement. (a model
// created along with a SceneGraph for simulation would also have input ports
// to interact with that SceneGraph).
MultibodyPlant<double> acrobot;
MultibodyPlant<double> acrobot(0.0);
Parser parser(&acrobot);
parser.AddModelFromFile(full_name);
// We are done defining the model.
Expand Down
2 changes: 1 addition & 1 deletion examples/multibody/cart_pole/test/cart_pole_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ class CartPoleTest : public ::testing::Test {
}

protected:
MultibodyPlant<double> cart_pole_;
MultibodyPlant<double> cart_pole_{0.0};
const PrismaticJoint<double>* cart_slider_{nullptr};
const RevoluteJoint<double>* pole_pin_{nullptr};
std::unique_ptr<Context<double>> context_;
Expand Down
2 changes: 1 addition & 1 deletion examples/pendulum/print_symbolic_dynamics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ VectorX<Expression> PendulumPlantDynamics() {
VectorX<Expression> MultibodyPlantDynamics() {
// Load the Pendulum.urdf into a symbolic MultibodyPlant.
const char* const urdf_path = "drake/examples/pendulum/Pendulum.urdf";
MultibodyPlant<double> plant;
MultibodyPlant<double> plant(0.0);
Parser parser(&plant);
parser.AddModelFromFile(FindResourceOrThrow(urdf_path));
plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ int DoMain() {
// (only) to extract joint velocity ordering.
const std::string full_name =
FindResourceOrThrow("drake/examples/planar_gripper/planar_gripper.sdf");
MultibodyPlant<double> control_plant;
MultibodyPlant<double> control_plant(0.0);
multibody::Parser(&control_plant).AddModelFromFile(full_name);
WeldGripperFrames<double>(&control_plant);
control_plant.Finalize();
Expand Down
4 changes: 2 additions & 2 deletions examples/planar_gripper/test/planar_gripper_common_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ GTEST_TEST(ReorderKeyframesTest, Test) {
// Create the plant which defines the ordering.
const std::string full_name =
FindResourceOrThrow("drake/examples/planar_gripper/planar_gripper.sdf");
MultibodyPlant<double> plant;
MultibodyPlant<double> plant(0.0);
multibody::Parser(&plant).AddModelFromFile(full_name, "gripper");
WeldGripperFrames(&plant);
plant.Finalize();
Expand Down Expand Up @@ -84,7 +84,7 @@ GTEST_TEST(ReorderKeyframesTest, Test) {

// Test throw when plant positions don't match number of expected planar
// gripper joints.
MultibodyPlant<double> bad_plant;
MultibodyPlant<double> bad_plant(0.0);
multibody::Parser(&bad_plant).AddModelFromFile(full_name, "gripper");
WeldGripperFrames(&bad_plant);
const std::string extra_model_name =
Expand Down
2 changes: 1 addition & 1 deletion examples/quadrotor/quadrotor_geometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ QuadrotorGeometry::QuadrotorGeometry(
// Use (temporary) MultibodyPlant to parse the urdf and setup the
// scene_graph.
// TODO(SeanCurtis-TRI): Update this on resolution of #10775.
multibody::MultibodyPlant<double> mbp;
multibody::MultibodyPlant<double> mbp(0.0);
multibody::Parser parser(&mbp, scene_graph);

auto model_id = parser.AddModelFromFile(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ TEST_P(ParseTest, Quantities) {
"drake/manipulation/models/allegro_hand_description/{}/"
"allegro_hand_description_left.{}", file_extension, file_extension));

MultibodyPlant<double> plant;
MultibodyPlant<double> plant(0.0);
Parser parser(&plant);
const ModelInstanceIndex right_hand_index =
parser.AddModelFromFile(path_right);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ GTEST_TEST(DualIiwa14PolytopeCollisionTest, TestLoadTree) {
"drake/manipulation/models/iiwa_description/urdf/"
"dual_iiwa14_polytope_collision.urdf"));

multibody::MultibodyPlant<double> plant;
multibody::MultibodyPlant<double> plant(0.0);
multibody::Parser parser(&plant);
parser.AddModelFromFile(kPath);
plant.Finalize();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ GTEST_TEST(JacoArmTest, TestLoad6DofTree) {
"drake/manipulation/models/jaco_description/urdf/"
"j2n6s300.urdf"));

multibody::MultibodyPlant<double> plant;
multibody::MultibodyPlant<double> plant(0.0);
multibody::Parser parser(&plant);
parser.AddModelFromFile(kPath);

Expand All @@ -41,7 +41,7 @@ GTEST_TEST(JacoArmTest, TestLoad7DofTree) {
"drake/manipulation/models/jaco_description/urdf/"
"j2s7s300.urdf"));

multibody::MultibodyPlant<double> plant;
multibody::MultibodyPlant<double> plant(0.0);
multibody::Parser parser(&plant);
parser.AddModelFromFile(kPath);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ GTEST_TEST(Wsg50DescriptionTest, TestMeshCollisionModelLoadTree) {
"drake/manipulation/models/wsg_50_description/urdf/"
"wsg_50_mesh_collision.urdf"));

multibody::MultibodyPlant<double> plant;
multibody::MultibodyPlant<double> plant(0.0);
multibody::Parser parser(&plant);
parser.AddModelFromFile(kPath);
plant.Finalize();
Expand Down
2 changes: 1 addition & 1 deletion manipulation/planner/robot_plan_interpolator.h
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ class RobotPlanInterpolator : public systems::LeafSystem<double> {
const int plan_input_port_{};
int state_output_port_{-1};
int acceleration_output_port_{-1};
multibody::MultibodyPlant<double> plant_;
multibody::MultibodyPlant<double> plant_{0.0};
const InterpolatorType interp_type_;
};

Expand Down
2 changes: 1 addition & 1 deletion manipulation/schunk_wsg/test/schunk_wsg_constants_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ namespace {
// Test that the constants defined in schunk_wsg_constants.h are
// correct wrt `models/schunk_wsg_50.sdf`.
GTEST_TEST(SchunkWsgConstantTest, ConstantTest) {
multibody::MultibodyPlant<double> plant;
multibody::MultibodyPlant<double> plant(0.0);
multibody::Parser parser(&plant);
parser.AddModelFromFile(FindResourceOrThrow(
"drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"));
Expand Down
2 changes: 1 addition & 1 deletion manipulation/util/geometry_inspector.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ def main():
scene_graph = builder.AddSystem(SceneGraph())

# Construct a MultibodyPlant.
plant = MultibodyPlant()
plant = MultibodyPlant(0.0)
plant.RegisterAsSourceForSceneGraph(scene_graph)

# Create the parser.
Expand Down
2 changes: 1 addition & 1 deletion manipulation/util/show_model.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ def main():

# Construct Plant + SceneGraph.
builder = DiagramBuilder()
plant = builder.AddSystem(MultibodyPlant())
plant = builder.AddSystem(MultibodyPlant(0.0))
scene_graph = builder.AddSystem(SceneGraph())
plant.RegisterAsSourceForSceneGraph(scene_graph)
builder.Connect(
Expand Down
2 changes: 1 addition & 1 deletion multibody/benchmarks/acrobot/make_acrobot_plant.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ using drake::math::RigidTransformd;
std::unique_ptr<MultibodyPlant<double>>
MakeAcrobotPlant(const AcrobotParameters& params, bool finalize,
SceneGraph<double>* scene_graph) {
auto plant = std::make_unique<MultibodyPlant<double>>();
auto plant = std::make_unique<MultibodyPlant<double>>(0.0);

// COM's positions in each link (L1/L2) frame:
// Frame L1's origin is located at the shoulder outboard frame.
Expand Down
2 changes: 1 addition & 1 deletion multibody/benchmarks/pendulum/make_pendulum_plant.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ using geometry::Sphere;
std::unique_ptr<MultibodyPlant<double>>
MakePendulumPlant(const PendulumParameters& params,
SceneGraph<double>* scene_graph) {
auto plant = std::make_unique<MultibodyPlant<double>>();
auto plant = std::make_unique<MultibodyPlant<double>>(0.0);

// Position of the com of the pendulum's body (in this case a point mass) in
// the body's frame. The body's frame's origin Bo is defined to be at the
Expand Down
4 changes: 2 additions & 2 deletions multibody/hydroelastics/test/hydroelastic_engine_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ GeometryId AddRigidBody(MultibodyPlant<double>* plant,
}

GTEST_TEST(HydroelasticEngine, CombineSoftAndRigidMaterialProperties) {
MultibodyPlant<double> plant;
MultibodyPlant<double> plant(0.0);
SceneGraph<double> scene_graph;
plant.RegisterAsSourceForSceneGraph(&scene_graph);

Expand All @@ -74,7 +74,7 @@ GTEST_TEST(HydroelasticEngine, CombineSoftAndRigidMaterialProperties) {
}

GTEST_TEST(HydroelasticEngine, CombineSoftAndSoftMaterialProperties) {
MultibodyPlant<double> plant;
MultibodyPlant<double> plant(0.0);
SceneGraph<double> scene_graph;
plant.RegisterAsSourceForSceneGraph(&scene_graph);

Expand Down
2 changes: 1 addition & 1 deletion multibody/parsing/test/common_parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class MultibodyPlantLinkTests :
}

protected:
MultibodyPlant<double> plant_;
MultibodyPlant<double> plant_{0.0};
geometry::SceneGraph<double> scene_graph_;
const std::string base_name_{"drake/multibody/parsing/test/"
"links_with_visuals_and_collisions"};
Expand Down
Loading

0 comments on commit bc83ee2

Please sign in to comment.