def add_rope(plant, scene_graph, rope_config, X_W, rope_name="rope"): parser = Parser(plant, scene_graph) rope_sdf = generate_rope_sdf_from_config(rope_config, rope_name) rope_model = parser.AddModelFromString(file_contents=rope_sdf, file_type="sdf", model_name=rope_name) plant.WeldFrames(plant.world_frame(), plant.GetFrameByName(f"{rope_name}_capsule_1"), X_W) return rope_model
def test_strict(self): plant = MultibodyPlant(time_step=0.01) parser = Parser(plant=plant) model = """<robot name='robot' version='0.99'> <link name='a'/> </robot>""" parser.AddModelFromString(file_contents=model, file_type='urdf', model_name='lax') parser.SetStrictParsing() with self.assertRaises(RuntimeError) as e: result = parser.AddModelFromString(file_contents=model, file_type='urdf', model_name='strict') pattern = r'.*version.*ignored.*' message = str(e.exception) match = re.match(pattern, message) self.assertTrue(match, f'"{message}" does not match "{pattern}"')
def test_parser_string(self): """Checks parsing from a string (not file_name).""" sdf_file = FindResourceOrThrow( "drake/multibody/benchmarks/acrobot/acrobot.sdf") with open(sdf_file, "r") as f: sdf_contents = f.read() plant = MultibodyPlant(time_step=0.01) parser = Parser(plant=plant) result = parser.AddModelFromString( file_contents=sdf_contents, file_type="sdf") self.assertIsInstance(result, ModelInstanceIndex)