def test_multibody_plant_api_via_parsing(self):
     # TODO(eric.cousineau): Decouple this when construction can be done
     # without parsing.
     # This a subset of `multibody_plant_sdf_parser_test.cc`.
     file_name = FindResourceOrThrow(
         "drake/multibody/benchmarks/acrobot/acrobot.sdf")
     plant = MultibodyPlant(time_step=0.01)
     model_instance = AddModelFromSdfFile(
         file_name=file_name, plant=plant, scene_graph=None)
     self.assertIsInstance(model_instance, ModelInstanceIndex)
     plant.Finalize()
     benchmark = MakeAcrobotPlant(AcrobotParameters(), True)
     self.assertEqual(plant.num_bodies(), benchmark.num_bodies())
     self.assertEqual(plant.num_joints(), benchmark.num_joints())
     self.assertEqual(plant.num_actuators(), benchmark.num_actuators())
     self.assertEqual(
         plant.num_model_instances(), benchmark.num_model_instances() + 1)
     self.assertEqual(plant.num_positions(), benchmark.num_positions())
     self.assertEqual(
         plant.num_positions(model_instance=model_instance),
         benchmark.num_positions())
     self.assertEqual(
         plant.num_velocities(), benchmark.num_velocities())
     self.assertEqual(
         plant.num_multibody_states(), benchmark.num_multibody_states())
     self.assertEqual(
         plant.num_actuated_dofs(), benchmark.num_actuated_dofs())
     self.assertTrue(plant.is_finalized())
     self.assertTrue(plant.HasBodyNamed(name="Link1"))
     self.assertTrue(plant.HasJointNamed(name="ShoulderJoint"))
     shoulder = plant.GetJointByName(name="ShoulderJoint")
     self._test_joint_api(shoulder)
     np.testing.assert_array_equal(shoulder.lower_limits(), [-np.inf])
     np.testing.assert_array_equal(shoulder.upper_limits(), [np.inf])
     self._test_joint_actuator_api(
         plant.GetJointActuatorByName(name="ElbowJoint"))
     self._test_body_api(plant.GetBodyByName(name="Link1"))
     self.assertIs(
         plant.GetBodyByName(name="Link1"),
         plant.GetBodyByName(name="Link1", model_instance=model_instance))
     self._test_frame_api(plant.GetFrameByName(name="Link1"))
     self.assertIs(
         plant.GetFrameByName(name="Link1"),
         plant.GetFrameByName(name="Link1", model_instance=model_instance))
     self.assertIsInstance(
         plant.get_actuation_input_port(), InputPort)
     self.assertIsInstance(
         plant.get_continuous_state_output_port(), OutputPort)
     self.assertIsInstance(
         plant.get_contact_results_output_port(), OutputPort)
Esempio n. 2
0
 def test_multibody_plant_api_via_parsing(self):
     # TODO(eric.cousineau): Decouple this when construction can be done
     # without parsing.
     # This a subset of `multibody_plant_sdf_parser_test.cc`.
     file_name = FindResourceOrThrow(
         "drake/multibody/benchmarks/acrobot/acrobot.sdf")
     plant = MultibodyPlant(time_step=0.01)
     model_instance = Parser(plant).AddModelFromFile(file_name)
     self.assertIsInstance(model_instance, ModelInstanceIndex)
     plant.Finalize()
     benchmark = MakeAcrobotPlant(AcrobotParameters(), True)
     self.assertEqual(plant.num_bodies(), benchmark.num_bodies())
     self.assertEqual(plant.num_joints(), benchmark.num_joints())
     self.assertEqual(plant.num_actuators(), benchmark.num_actuators())
     self.assertEqual(plant.num_model_instances(),
                      benchmark.num_model_instances() + 1)
     self.assertEqual(plant.num_positions(), benchmark.num_positions())
     self.assertEqual(plant.num_positions(model_instance=model_instance),
                      benchmark.num_positions())
     self.assertEqual(plant.num_velocities(), benchmark.num_velocities())
     self.assertEqual(plant.num_multibody_states(),
                      benchmark.num_multibody_states())
     self.assertEqual(plant.num_actuated_dofs(),
                      benchmark.num_actuated_dofs())
     self.assertTrue(plant.is_finalized())
     self.assertTrue(plant.HasBodyNamed(name="Link1"))
     self.assertTrue(
         plant.HasBodyNamed(name="Link1", model_instance=model_instance))
     self.assertTrue(plant.HasJointNamed(name="ShoulderJoint"))
     self.assertTrue(
         plant.HasJointNamed(name="ShoulderJoint",
                             model_instance=model_instance))
     shoulder = plant.GetJointByName(name="ShoulderJoint")
     self._test_joint_api(shoulder)
     np.testing.assert_array_equal(shoulder.position_lower_limits(),
                                   [-np.inf])
     np.testing.assert_array_equal(shoulder.position_upper_limits(),
                                   [np.inf])
     self.assertIs(
         shoulder,
         plant.GetJointByName(name="ShoulderJoint",
                              model_instance=model_instance))
     self._test_joint_actuator_api(
         plant.GetJointActuatorByName(name="ElbowJoint"))
     self._test_body_api(plant.GetBodyByName(name="Link1"))
     self.assertIs(
         plant.GetBodyByName(name="Link1"),
         plant.GetBodyByName(name="Link1", model_instance=model_instance))
     self.assertEqual(len(plant.GetBodyIndices(model_instance)), 2)
     self._test_frame_api(plant.GetFrameByName(name="Link1"))
     self.assertIs(
         plant.GetFrameByName(name="Link1"),
         plant.GetFrameByName(name="Link1", model_instance=model_instance))
     self.assertEqual(model_instance,
                      plant.GetModelInstanceByName(name="acrobot"))
     self.assertIsInstance(plant.get_actuation_input_port(), InputPort)
     self.assertIsInstance(plant.get_state_output_port(), OutputPort)
     # Smoke test of deprecated methods.
     with catch_drake_warnings(expected_count=2):
         plant.get_continuous_state_output_port()
         plant.get_continuous_state_output_port(model_instance)
     self.assertIsInstance(plant.get_contact_results_output_port(),
                           OutputPort)
     self.assertIsInstance(plant.num_frames(), int)
     self.assertIsInstance(plant.get_body(body_index=BodyIndex(0)), Body)
     self.assertIs(shoulder, plant.get_joint(joint_index=JointIndex(0)))
     self.assertIsInstance(
         plant.get_joint_actuator(actuator_index=JointActuatorIndex(0)),
         JointActuator)
     self.assertIsInstance(plant.get_frame(frame_index=FrameIndex(0)),
                           Frame)
     self.assertEqual(
         "acrobot",
         plant.GetModelInstanceName(model_instance=model_instance))