def test_subgraph_add_to_copying(self): """Ensures that index ordering is generally the same when copying a plant using a MultibodyPlantSubgraph.add_to.""" # TODO(eric.cousineau): Increas number of bodies for viz, once # `create_manual_map` can acommodate it. plant_a, scene_graph_a, _ = self.make_arbitrary_multibody_stuff( num_bodies=1) # Check for general ordering with full subgraph "cloning". builder_b = DiagramBuilder() plant_b, scene_graph_b = AddMultibodyPlantSceneGraph( builder_b, plant_a.time_step()) subgraph_a = mut.MultibodyPlantSubgraph( mut.get_elements_from_plant(plant_a, scene_graph_a)) a_to_b = subgraph_a.add_to(plant_b, scene_graph_b) plant_b.Finalize() util.assert_plant_equals(plant_a, scene_graph_a, plant_b, scene_graph_b) a_to_b_expected = self.create_manual_map(plant_a, scene_graph_a, plant_b, scene_graph_b) self.assertEqual(a_to_b, a_to_b_expected) if VISUALIZE: for model in me.get_model_instances(plant_b): util.build_with_no_control(builder_b, plant_b, model) print("test_subgraph_add_to_copying") DrakeVisualizer.AddToBuilder(builder_b, scene_graph_b) diagram = builder_b.Build() simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.) simulator.Initialize() diagram.Publish(simulator.get_context()) simulator.AdvanceTo(1.)
def test_viewer_applet(self): """Check that _ViewerApplet doesn't crash when receiving messages. Note that many geometry types are not yet covered by this test. """ # Create the device under test. dut = mut.Meldis() meshcat = dut.meshcat lcm = dut._lcm # The path is created by the constructor. self.assertEqual(meshcat.HasPath("/DRAKE_VIEWER"), True) # Enqueue the load + draw messages. sdf_file = FindResourceOrThrow( "drake/multibody/benchmarks/acrobot/acrobot.sdf") builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) parser = Parser(plant=plant) parser.AddModelFromFile(sdf_file) plant.Finalize() DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph, lcm=lcm) diagram = builder.Build() context = diagram.CreateDefaultContext() diagram.Publish(context) # The geometry isn't registered until the load is processed. link_path = "/DRAKE_VIEWER/2/plant/acrobot/Link2/0" self.assertEqual(meshcat.HasPath(link_path), False) # Process the load + draw; make sure the geometry exists now. lcm.HandleSubscriptions(timeout_millis=0) dut._invoke_subscriptions() self.assertEqual(meshcat.HasPath(link_path), True)
def connect_visualizers(builder, plant, scene_graph): # Connect this to drake_visualizer. DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph) # Connect to Meshcat. If the consuming application needs to connect, # e.g., JointSliders, the meshcat instance is required. meshcat = None if args.meshcat: meshcat = Meshcat() meshcat_vis_params = MeshcatVisualizerParams() meshcat_vis_params.role = args.meshcat_role MeshcatVisualizerCpp.AddToBuilder(builder=builder, scene_graph=scene_graph, meshcat=meshcat, params=meshcat_vis_params) if args.browser_new is not None: url = meshcat.web_url() webbrowser.open(url=url, new=args.browser_new) else: if args.browser_new is not None: args_parser.error("-w / --open-window require --meshcat") # Connect to PyPlot. if args.pyplot: pyplot = ConnectPlanarSceneGraphVisualizer(builder, scene_graph) return meshcat
def experiment(start_state, force_schedule, sleeptime=None): global experiment_count experiment_count += 1 if experiment_count % 10 == 0: print(f"{experiment_count} experiments run so far...") builder = DiagramBuilder() mbp, sg = make_mbp(builder) mbp.Finalize() DrakeVisualizer.AddToBuilder(builder, sg, lcm=global_lcm_ftw) thrusters = add_thrusters(builder, mbp) breaks = [0] for _, t in force_schedule: breaks.append(breaks[-1] + t) forces = np.array([f for f, t in force_schedule] + [force_schedule[-1][0]]) force_traj = PiecewisePolynomial.ZeroOrderHold(breaks, forces.transpose()) controller = builder.AddSystem(TrajectorySource(force_traj)) builder.Connect(controller.get_output_port(), thrusters.get_command_input_port()) diagram = builder.Build() simulator = Simulator(diagram) mbp_context = diagram.GetSubsystemContext(mbp, simulator.get_context()) mbp.SetPositionsAndVelocities(mbp_context, start_state) for step in range(int(1000 * breaks[-1])): simulator.AdvanceTo(0.001 * step) mbp_context = diagram.GetSubsystemContext(mbp, simulator.get_context()) if sleeptime: time.sleep(sleeptime) return mbp.GetPositionsAndVelocities( diagram.GetSubsystemContext(mbp, simulator.get_context()))
def main(): parser = argparse.ArgumentParser(description=__doc__) parser.add_argument( "--target_realtime_rate", type=float, default=1.0, help="Desired rate relative to real time. See documentation for " "Simulator::set_target_realtime_rate() for details.") parser.add_argument("--simulation_time", type=float, default=10.0, help="Desired duration of the simulation in seconds.") parser.add_argument( "--time_step", type=float, default=0., help="If greater than zero, the plant is modeled as a system with " "discrete updates and period equal to this time_step. " "If 0, the plant is modeled as a continuous system.") args = parser.parse_args() file_name = FindResourceOrThrow( "drake/examples/multibody/cart_pole/cart_pole.sdf") builder = DiagramBuilder() scene_graph = builder.AddSystem(SceneGraph()) cart_pole = builder.AddSystem(MultibodyPlant(time_step=args.time_step)) cart_pole.RegisterAsSourceForSceneGraph(scene_graph) Parser(plant=cart_pole).AddModelFromFile(file_name) cart_pole.Finalize() assert cart_pole.geometry_source_is_registered() builder.Connect(scene_graph.get_query_output_port(), cart_pole.get_geometry_query_input_port()) builder.Connect( cart_pole.get_geometry_poses_output_port(), scene_graph.get_source_pose_port(cart_pole.get_source_id())) DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph) diagram = builder.Build() diagram_context = diagram.CreateDefaultContext() cart_pole_context = diagram.GetMutableSubsystemContext( cart_pole, diagram_context) cart_pole.get_actuation_input_port().FixValue(cart_pole_context, 0) cart_slider = cart_pole.GetJointByName("CartSlider") pole_pin = cart_pole.GetJointByName("PolePin") cart_slider.set_translation(context=cart_pole_context, translation=0.) pole_pin.set_angle(context=cart_pole_context, angle=2.) simulator = Simulator(diagram, diagram_context) simulator.set_publish_every_time_step(False) simulator.set_target_realtime_rate(args.target_realtime_rate) simulator.Initialize() simulator.AdvanceTo(args.simulation_time)
def _make_diagram(self, *, sdf_filename, visualizer_params, lcm): builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) parser = Parser(plant=plant) parser.AddModelFromFile(FindResourceOrThrow(sdf_filename)) plant.Finalize() DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph, params=visualizer_params, lcm=lcm) diagram = builder.Build() return diagram
def connect_visualizers(builder, plant, scene_graph): # Connect this to drake_visualizer. DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph) # Connect to Meshcat. if args.meshcat is not None: meshcat_viz = ConnectMeshcatVisualizer(builder, scene_graph, zmq_url=args.meshcat) # Connect to PyPlot. if args.pyplot: pyplot = ConnectPlanarSceneGraphVisualizer(builder, scene_graph)
def connect_visualizers(builder, plant, scene_graph): # Connect this to drake_visualizer. DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph) # Connect to Meshcat. if args.meshcat is not None: meshcat_viz = ConnectMeshcatVisualizer(builder, scene_graph, zmq_url=args.meshcat) # Connect to PyPlot. if args.pyplot: pyplot = builder.AddSystem(PlanarSceneGraphVisualizer(scene_graph)) builder.Connect(scene_graph.get_pose_bundle_output_port(), pyplot.get_input_port(0))
def make_ball_paddle(contact_model, contact_surface_representation, time_step): multibody_plant_config = \ MultibodyPlantConfig( time_step=time_step, contact_model=contact_model, contact_surface_representation=contact_surface_representation) # We pose the paddle, so that its top surface is on World's X-Y plane. # Intuitively we push it down 1 cm because the box is 2 cm thick. p_WPaddle_fixed = RigidTransform(RollPitchYaw(0, 0, 0), np.array([0, 0, -0.01])) builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlant(multibody_plant_config, builder) parser = Parser(plant) paddle_sdf_file_name = \ FindResourceOrThrow("drake/examples/hydroelastic/python_ball_paddle" "/paddle.sdf") paddle = parser.AddModelFromFile(paddle_sdf_file_name, model_name="paddle") plant.WeldFrames(frame_on_parent_F=plant.world_frame(), frame_on_child_M=plant.GetFrameByName("paddle", paddle), X_FM=p_WPaddle_fixed) ball_sdf_file_name = \ FindResourceOrThrow("drake/examples/hydroelastic/python_ball_paddle" "/ball.sdf") parser.AddModelFromFile(ball_sdf_file_name) # TODO(DamrongGuoy): Let users override hydroelastic modulus, dissipation, # and resolution hint from the two SDF files above. plant.Finalize() DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph) ConnectContactResultsToDrakeVisualizer(builder=builder, plant=plant, scene_graph=scene_graph) nx = plant.num_positions() + plant.num_velocities() state_logger = builder.AddSystem(VectorLogSink(nx)) builder.Connect(plant.get_state_output_port(), state_logger.get_input_port()) diagram = builder.Build() return diagram, plant, state_logger
def test_composition_array_with_scene_graph(self): """Tests subgraphs (post-finalize) with a scene graph. This time, using sugar from parse_as_multibody_plant_subgraph.""" # Create IIWA. iiwa_file = FindResourceOrThrow( "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_spheres_dense_elbow_collision.urdf") iiwa_subgraph, iiwa_model = mut.parse_as_multibody_plant_subgraph( iiwa_file) self.assertIsInstance(iiwa_subgraph, mut.MultibodyPlantSubgraph) self.assertIsInstance(iiwa_model, ModelInstanceIndex) # Make 10 copies of the IIWA in a line. builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, time_step=0.01) models = [] for i in range(10): sub_to_full = iiwa_subgraph.add_to( plant, scene_graph, model_instance_remap=f"iiwa_{i}") self.assertIsInstance(sub_to_full, mut.MultibodyPlantElementsMap) X_WB = RigidTransform(p=[i * 0.5, 0, 0]) model = sub_to_full.model_instances[iiwa_model] base_frame = plant.GetFrameByName("base", model) plant.WeldFrames(plant.world_frame(), base_frame, X_WB) models.append(model) plant.Finalize() if VISUALIZE: print("test_composition_array_with_scene_graph") DrakeVisualizer.AddToBuilder(builder, scene_graph) diagram = builder.Build() d_context = diagram.CreateDefaultContext() for i, model in enumerate(models): self.assertEqual(plant.GetModelInstanceName(model), f"iiwa_{i}") if VISUALIZE: print(" Visualize composite") Simulator(diagram, d_context.Clone()).Initialize() input(" Press enter...")
def main(): builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, time_step=0.0) path = subprocess.check_output([ 'venv/share/drake/common/resource_tool', '-print_resource_path', 'drake/examples/multibody/cart_pole/cart_pole.sdf', ]).strip() Parser(plant).AddModelFromFile(path) plant.Finalize() # Add to visualizer. DrakeVisualizer.AddToBuilder(builder, scene_graph) # Add controller. controller = builder.AddSystem(BalancingLQR(plant)) builder.Connect(plant.get_state_output_port(), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), plant.get_actuation_input_port()) diagram = builder.Build() # Set up a simulator to run this diagram. simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) context = simulator.get_mutable_context() # Simulate. duration = 8.0 for i in range(5): initial_state = UPRIGHT_STATE + 0.1 * np.random.randn(4) print(f"Iteration: {i}. Initial: {initial_state}") context.SetContinuousState(initial_state) context.SetTime(0.0) simulator.Initialize() simulator.AdvanceTo(duration)
def test_composition_gripper_workflow(self): """Tests subgraphs (pre-finalize) for composition, with a scene graph, welding bodies together across different subgraphs.""" # N.B. The frame-welding is done so that we can easily set the # positions of the IIWA / WSG without having to worry about / work # around the floating body coordinates. # Create IIWA. iiwa_builder = DiagramBuilder() iiwa_plant, iiwa_scene_graph = AddMultibodyPlantSceneGraph( iiwa_builder, time_step=0.) iiwa_file = FindResourceOrThrow( "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_spheres_dense_elbow_collision.urdf") iiwa_model = Parser(iiwa_plant).AddModelFromFile(iiwa_file, "iiwa") iiwa_plant.WeldFrames(iiwa_plant.world_frame(), iiwa_plant.GetFrameByName("base")) iiwa_plant.Finalize() if VISUALIZE: print("test_composition") DrakeVisualizer.AddToBuilder(iiwa_builder, iiwa_scene_graph) iiwa_diagram = iiwa_builder.Build() iiwa_subgraph = mut.MultibodyPlantSubgraph( mut.get_elements_from_plant(iiwa_plant, iiwa_scene_graph)) self.assertIsInstance(iiwa_subgraph, mut.MultibodyPlantSubgraph) iiwa_subgraph.remove_body(iiwa_plant.world_body()) # Create WSG. wsg_builder = DiagramBuilder() wsg_plant, wsg_scene_graph = AddMultibodyPlantSceneGraph(wsg_builder, time_step=0.) wsg_file = FindResourceOrThrow( "drake/manipulation/models/wsg_50_description/sdf/" "schunk_wsg_50.sdf") wsg_model = Parser(wsg_plant).AddModelFromFile(wsg_file, "gripper_model") wsg_plant.WeldFrames(wsg_plant.world_frame(), wsg_plant.GetFrameByName("__model__")) wsg_plant.Finalize() if VISUALIZE: DrakeVisualizer.AddToBuilder(wsg_builder, wsg_scene_graph) wsg_diagram = wsg_builder.Build() wsg_subgraph = mut.MultibodyPlantSubgraph( mut.get_elements_from_plant(wsg_plant, wsg_scene_graph)) self.assertIsInstance(wsg_subgraph, mut.MultibodyPlantSubgraph) wsg_subgraph.remove_body(wsg_plant.world_body()) builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, time_step=1e-3) iiwa_to_plant = iiwa_subgraph.add_to(plant, scene_graph) self.assertIsInstance(iiwa_to_plant, mut.MultibodyPlantElementsMap) wsg_to_plant = wsg_subgraph.add_to(plant, scene_graph) self.assertIsInstance(wsg_to_plant, mut.MultibodyPlantElementsMap) if VISUALIZE: DrakeVisualizer.AddToBuilder(builder, scene_graph) rpy_deg = np.array([90., 0., 90]) X_7G = RigidTransform(p=[0, 0, 0.114], rpy=RollPitchYaw(rpy_deg * np.pi / 180)) frame_7 = plant.GetFrameByName("iiwa_link_7") frame_G = plant.GetFrameByName("body") plant.WeldFrames(frame_7, frame_G, X_7G) plant.Finalize() q_iiwa = [0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7] q_wsg = [-0.03, 0.03] iiwa_d_context = iiwa_diagram.CreateDefaultContext() iiwa_context = iiwa_plant.GetMyContextFromRoot(iiwa_d_context) iiwa_plant.SetPositions(iiwa_context, iiwa_model, q_iiwa) wsg_d_context = wsg_diagram.CreateDefaultContext() wsg_context = wsg_plant.GetMyContextFromRoot(wsg_d_context) wsg_plant.SetPositions(wsg_context, wsg_model, q_wsg) # Transfer state and briefly compare. diagram = builder.Build() d_context = diagram.CreateDefaultContext() context = plant.GetMyContextFromRoot(d_context) iiwa_to_plant.copy_state(iiwa_context, context) wsg_to_plant.copy_state(wsg_context, context) # Compare frames from sub-plants. util.compare_frame_poses(plant, context, iiwa_plant, iiwa_context, "base", "iiwa_link_7") util.compare_frame_poses(plant, context, wsg_plant, wsg_context, "body", "left_finger") # Visualize. if VISUALIZE: print(" Visualize IIWA") Simulator(iiwa_diagram, iiwa_d_context.Clone()).Initialize() input(" Press enter...") print(" Visualize WSG") Simulator(wsg_diagram, wsg_d_context.Clone()).Initialize() input(" Press enter...") print(" Visualize Composite") Simulator(diagram, d_context.Clone()).Initialize() input(" Press enter...")
def test_exploding_iiwa_sim(self): """ Shows a simulation of a falling + exploding IIWA which "changes topology" by being rebuilt without joints. """ builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, time_step=1e-3) iiwa_file = FindResourceOrThrow( "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_spheres_dense_elbow_collision.urdf") Parser(plant).AddModelFromFile(iiwa_file, "iiwa") # Add ground plane. X_FH = HalfSpace.MakePose([0, 0, 1], [0, 0, 0]) plant.RegisterCollisionGeometry(plant.world_body(), X_FH, HalfSpace(), "ground_plane_collision", CoulombFriction(0.8, 0.3)) plant.Finalize() # Loosey-goosey - no control. for model in me.get_model_instances(plant): util.build_with_no_control(builder, plant, model) if VISUALIZE: print("test_exploding_iiwa_sim") role = Role.kIllustration DrakeVisualizer.AddToBuilder( builder, scene_graph, params=DrakeVisualizerParams(role=role)) ConnectContactResultsToDrakeVisualizer(builder, plant, scene_graph) diagram = builder.Build() # Set up context. d_context = diagram.CreateDefaultContext() context = plant.GetMyContextFromRoot(d_context) # - Hoist IIWA up in the air. plant.SetFreeBodyPose(context, plant.GetBodyByName("base"), RigidTransform([0, 0, 1.])) # - Set joint velocities to "spin" it in the air. for joint in me.get_joints(plant): if isinstance(joint, RevoluteJoint): me.set_joint_positions(plant, context, joint, 0.7) me.set_joint_velocities(plant, context, joint, -5.) def monitor(d_context): # Stop the simulation once there's any contact. context = plant.GetMyContextFromRoot(d_context) query_object = plant.get_geometry_query_input_port().Eval(context) if query_object.HasCollisions(): return EventStatus.ReachedTermination(plant, "Contact") else: return EventStatus.DidNothing() # Forward simulate. simulator = Simulator(diagram, d_context) simulator.Initialize() simulator.set_monitor(monitor) if VISUALIZE: simulator.set_target_realtime_rate(1.) simulator.AdvanceTo(2.) # Try to push a bit further. simulator.clear_monitor() simulator.AdvanceTo(d_context.get_time() + 0.05) diagram.Publish(d_context) # Recreate simulator. builder_new = DiagramBuilder() plant_new, scene_graph_new = AddMultibodyPlantSceneGraph( builder_new, time_step=plant.time_step()) subgraph = mut.MultibodyPlantSubgraph( mut.get_elements_from_plant(plant, scene_graph)) # Remove all joints; make them floating bodies. for joint in me.get_joints(plant): subgraph.remove_joint(joint) # Remove massless bodies. # For more info, see: https://stackoverflow.com/a/62035705/7829525 for body in me.get_bodies(plant): if body is plant.world_body(): continue if body.default_mass() == 0.: subgraph.remove_body(body) # Finalize. to_new = subgraph.add_to(plant_new, scene_graph_new) plant_new.Finalize() if VISUALIZE: DrakeVisualizer.AddToBuilder( builder_new, scene_graph_new, params=DrakeVisualizerParams(role=role)) ConnectContactResultsToDrakeVisualizer(builder_new, plant_new, scene_graph_new) diagram_new = builder_new.Build() # Remap state. d_context_new = diagram_new.CreateDefaultContext() d_context_new.SetTime(d_context.get_time()) context_new = plant_new.GetMyContextFromRoot(d_context_new) to_new.copy_state(context, context_new) # Simulate. simulator_new = Simulator(diagram_new, d_context_new) simulator_new.Initialize() diagram_new.Publish(d_context_new) if VISUALIZE: simulator_new.set_target_realtime_rate(1.) simulator_new.AdvanceTo(context_new.get_time() + 2) if VISUALIZE: input(" Press enter...")
def _connect_visualizer(self): DrakeVisualizer.AddToBuilder(self.builder, self.scenegraph) self.meshcat = ConnectMeshcatVisualizer(self.builder, self.scenegraph, zmq_url="new", open_browser=False) self.meshcat.vis.jupyter_cell()
def _build_body_patches(self, use_random_colors, substitute_collocated_mesh_files): """ Generates body patches. self._patch_Blist stores a list of patches for each body (starting at body id 1). A body patch is a list of all 3D vertices of a piece of visual geometry. """ self._patch_Blist = {} self._patch_Blist_colors = {} memq_lcm = DrakeLcm("memq://") memq_lcm_subscriber = Subscriber(lcm=memq_lcm, channel="DRAKE_VIEWER_LOAD_ROBOT", lcm_type=lcmt_viewer_load_robot) # TODO(SeanCurtis-TRI): Use SceneGraph inspection instead of mocking # LCM and inspecting the generated message. DrakeVisualizer.DispatchLoadMessage(self._scene_graph, memq_lcm) memq_lcm.HandleSubscriptions(0) assert memq_lcm_subscriber.count > 0 load_robot_msg = memq_lcm_subscriber.message # Spawn a random color generator, in case we need to pick random colors # for some bodies. Each body will be given a unique color when using # this random generator, with each visual element of the body colored # the same. color = iter( plt.cm.rainbow(np.linspace(0, 1, load_robot_msg.num_links))) for i in range(load_robot_msg.num_links): link = load_robot_msg.link[i] this_body_patches = [] this_body_colors = [] this_color = next(color) for j in range(link.num_geom): geom = link.geom[j] # MultibodyPlant currently sets alpha=0 to make collision # geometry "invisible". Ignore those geometries here. if geom.color[3] == 0: continue # Short-circuit if the geometry scale is invalid. # (All uses of float data should be strictly positive: # edge lengths for boxes, radius and length for # spheres and cylinders, and scaling for meshes.) if not all([x > 0 for x in geom.float_data]): continue X_BG = RigidTransform( RotationMatrix(Quaternion(geom.quaternion)), geom.position) if geom.type == geom.BOX: assert geom.num_float_data == 3 # Draw a bounding box. patch_G = np.vstack( (geom.float_data[0] / 2. * np.array([-1, -1, 1, 1, -1, -1, 1, 1]), geom.float_data[1] / 2. * np.array([-1, 1, -1, 1, -1, 1, -1, 1]), geom.float_data[2] / 2. * np.array([-1, -1, -1, -1, 1, 1, 1, 1]))) elif geom.type == geom.SPHERE: assert geom.num_float_data == 1 radius = geom.float_data[0] lati, longi = np.meshgrid(np.arange(0., 2. * math.pi, 0.5), np.arange(0., 2. * math.pi, 0.5)) lati = lati.ravel() longi = longi.ravel() patch_G = np.vstack([ np.sin(lati) * np.cos(longi), np.sin(lati) * np.sin(longi), np.cos(lati) ]) patch_G *= radius elif geom.type == geom.CYLINDER: assert geom.num_float_data == 2 radius = geom.float_data[0] length = geom.float_data[1] # In the lcm geometry, cylinders are along +z # https://github.com/RobotLocomotion/drake/blob/last_sha_with_original_matlab/drake/matlab/systems/plants/RigidBodyCylinder.m # Two circles: one at bottom, one at top. sample_pts = np.arange(0., 2. * math.pi, 0.25) patch_G = np.hstack([ np.array([[ radius * math.cos(pt), radius * math.sin(pt), -length / 2. ], [ radius * math.cos(pt), radius * math.sin(pt), length / 2. ]]).T for pt in sample_pts ]) elif geom.type == geom.MESH: filename = geom.string_data base, ext = os.path.splitext(filename) if (ext.lower() != ".obj" and substitute_collocated_mesh_files): # Check for a co-located .obj file (case insensitive). for f in glob.glob(base + '.*'): if f[-4:].lower() == '.obj': filename = f break if filename[-4:].lower() != '.obj': raise RuntimeError( f"The given file {filename} is not " f"supported and no alternate {base}" ".obj could be found.") if not os.path.exists(filename): raise FileNotFoundError(errno.ENOENT, os.strerror(errno.ENOENT), filename) # Get mesh scaling. scale = geom.float_data[0] mesh = ReadObjToSurfaceMesh(filename, scale) patch_G = np.vstack([v.r_MV() for v in mesh.vertices()]) # Only store the vertices of the (3D) convex hull of the # mesh, as any interior vertices will still be interior # vertices after projection, and will therefore be removed # in _update_body_fill_verts(). hull = spatial.ConvexHull(patch_G) patch_G = np.vstack([patch_G[v, :] for v in hull.vertices]).T else: print("UNSUPPORTED GEOMETRY TYPE {} IGNORED".format( geom.type)) continue # Compute pose in body. patch_B = X_BG @ patch_G # Close path if not closed. if (patch_B[:, -1] != patch_B[:, 0]).any(): patch_B = np.hstack((patch_B, patch_B[:, 0][np.newaxis].T)) this_body_patches.append(patch_B) if use_random_colors: this_body_colors.append(this_color) else: this_body_colors.append(geom.color) self._patch_Blist[link.name] = this_body_patches self._patch_Blist_colors[link.name] = this_body_colors
def main(): parser = argparse.ArgumentParser(description=__doc__) parser.add_argument( "--target_realtime_rate", type=float, default=1.0, help="Desired rate relative to real time. See documentation for " "Simulator::set_target_realtime_rate() for details.") parser.add_argument( "--duration", type=float, default=np.inf, help="Desired duration of the simulation in seconds.") parser.add_argument( "--hardware", action='store_true', help="Use the ManipulationStationHardwareInterface instead of an " "in-process simulation.") parser.add_argument( "--test", action='store_true', help="Disable opening the gui window for testing.") parser.add_argument( "--filter_time_const", type=float, default=0.1, help="Time constant for the first order low pass filter applied to" "the teleop commands") parser.add_argument( "--velocity_limit_factor", type=float, default=1.0, help="This value, typically between 0 and 1, further limits the " "iiwa14 joint velocities. It multiplies each of the seven " "pre-defined joint velocity limits. " "Note: The pre-defined velocity limits are specified by " "iiwa14_velocity_limits, found in this python file.") parser.add_argument( '--setup', type=str, default='manipulation_class', help="The manipulation station setup to simulate. ", choices=['manipulation_class', 'clutter_clearing', 'planar']) parser.add_argument( '--schunk_collision_model', type=str, default='box', help="The Schunk collision model to use for simulation. ", choices=['box', 'box_plus_fingertip_spheres']) MeshcatVisualizer.add_argparse_argument(parser) args = parser.parse_args() builder = DiagramBuilder() if args.hardware: station = builder.AddSystem(ManipulationStationHardwareInterface()) station.Connect(wait_for_cameras=False) else: station = builder.AddSystem(ManipulationStation()) if args.schunk_collision_model == "box": schunk_model = SchunkCollisionModel.kBox elif args.schunk_collision_model == "box_plus_fingertip_spheres": schunk_model = SchunkCollisionModel.kBoxPlusFingertipSpheres # Initializes the chosen station type. if args.setup == 'manipulation_class': station.SetupManipulationClassStation( schunk_model=schunk_model) station.AddManipulandFromFile( "drake/examples/manipulation_station/models/" + "061_foam_brick.sdf", RigidTransform(RotationMatrix.Identity(), [0.6, 0, 0])) elif args.setup == 'clutter_clearing': station.SetupClutterClearingStation( schunk_model=schunk_model) ycb_objects = CreateClutterClearingYcbObjectList() for model_file, X_WObject in ycb_objects: station.AddManipulandFromFile(model_file, X_WObject) elif args.setup == 'planar': station.SetupPlanarIiwaStation( schunk_model=schunk_model) station.AddManipulandFromFile( "drake/examples/manipulation_station/models/" + "061_foam_brick.sdf", RigidTransform(RotationMatrix.Identity(), [0.6, 0, 0])) station.Finalize() # If using meshcat, don't render the cameras, since RgbdCamera # rendering only works with drake-visualizer. Without this check, # running this code in a docker container produces libGL errors. if args.meshcat: meshcat = ConnectMeshcatVisualizer( builder, output_port=station.GetOutputPort("geometry_query"), zmq_url=args.meshcat, open_browser=args.open_browser) if args.setup == 'planar': meshcat.set_planar_viewpoint() elif args.setup == 'planar': pyplot_visualizer = builder.AddSystem(PlanarSceneGraphVisualizer( station.get_scene_graph())) builder.Connect(station.GetOutputPort("pose_bundle"), pyplot_visualizer.get_input_port(0)) else: DrakeVisualizer.AddToBuilder(builder, station.GetOutputPort("query_object")) image_to_lcm_image_array = builder.AddSystem( ImageToLcmImageArrayT()) image_to_lcm_image_array.set_name("converter") for name in station.get_camera_names(): cam_port = ( image_to_lcm_image_array .DeclareImageInputPort[PixelType.kRgba8U]( "camera_" + name)) builder.Connect( station.GetOutputPort("camera_" + name + "_rgb_image"), cam_port) image_array_lcm_publisher = builder.AddSystem( LcmPublisherSystem.Make( channel="DRAKE_RGBD_CAMERA_IMAGES", lcm_type=image_array_t, lcm=None, publish_period=0.1, use_cpp_serializer=True)) image_array_lcm_publisher.set_name("rgbd_publisher") builder.Connect( image_to_lcm_image_array.image_array_t_msg_output_port(), image_array_lcm_publisher.get_input_port(0)) robot = station.get_controller_plant() params = DifferentialInverseKinematicsParameters(robot.num_positions(), robot.num_velocities()) time_step = 0.005 params.set_timestep(time_step) # True velocity limits for the IIWA14 (in rad, rounded down to the first # decimal) iiwa14_velocity_limits = np.array([1.4, 1.4, 1.7, 1.3, 2.2, 2.3, 2.3]) if args.setup == 'planar': # Extract the 3 joints that are not welded in the planar version. iiwa14_velocity_limits = iiwa14_velocity_limits[1:6:2] # The below constant is in body frame. params.set_end_effector_velocity_gain([1, 0, 0, 0, 1, 1]) # Stay within a small fraction of those limits for this teleop demo. factor = args.velocity_limit_factor params.set_joint_velocity_limits((-factor*iiwa14_velocity_limits, factor*iiwa14_velocity_limits)) differential_ik = builder.AddSystem(DifferentialIK( robot, robot.GetFrameByName("iiwa_link_7"), params, time_step)) builder.Connect(differential_ik.GetOutputPort("joint_position_desired"), station.GetInputPort("iiwa_position")) teleop = builder.AddSystem(EndEffectorTeleop(args.setup == 'planar')) if args.test: teleop.window.withdraw() # Don't display the window when testing. filter = builder.AddSystem( FirstOrderLowPassFilter(time_constant=args.filter_time_const, size=6)) builder.Connect(teleop.get_output_port(0), filter.get_input_port(0)) builder.Connect(filter.get_output_port(0), differential_ik.GetInputPort("rpy_xyz_desired")) wsg_buttons = builder.AddSystem(SchunkWsgButtons(teleop.window)) builder.Connect(wsg_buttons.GetOutputPort("position"), station.GetInputPort("wsg_position")) builder.Connect(wsg_buttons.GetOutputPort("force_limit"), station.GetInputPort("wsg_force_limit")) # When in regression test mode, log our joint velocities to later check # that they were sufficiently quiet. num_iiwa_joints = station.num_iiwa_joints() if args.test: iiwa_velocities = builder.AddSystem(SignalLogger(num_iiwa_joints)) builder.Connect(station.GetOutputPort("iiwa_velocity_estimated"), iiwa_velocities.get_input_port(0)) else: iiwa_velocities = None diagram = builder.Build() simulator = Simulator(diagram) # This is important to avoid duplicate publishes to the hardware interface: simulator.set_publish_every_time_step(False) station_context = diagram.GetMutableSubsystemContext( station, simulator.get_mutable_context()) station.GetInputPort("iiwa_feedforward_torque").FixValue( station_context, np.zeros(num_iiwa_joints)) # If the diagram is only the hardware interface, then we must advance it a # little bit so that first LCM messages get processed. A simulated plant is # already publishing correct positions even without advancing, and indeed # we must not advance a simulated plant until the sliders and filters have # been initialized to match the plant. if args.hardware: simulator.AdvanceTo(1e-6) q0 = station.GetOutputPort("iiwa_position_measured").Eval( station_context) differential_ik.parameters.set_nominal_joint_position(q0) teleop.SetPose(differential_ik.ForwardKinematics(q0)) filter.set_initial_output_value( diagram.GetMutableSubsystemContext( filter, simulator.get_mutable_context()), teleop.get_output_port(0).Eval(diagram.GetMutableSubsystemContext( teleop, simulator.get_mutable_context()))) differential_ik.SetPositions(diagram.GetMutableSubsystemContext( differential_ik, simulator.get_mutable_context()), q0) simulator.set_target_realtime_rate(args.target_realtime_rate) simulator.AdvanceTo(args.duration) # Ensure that our initialization logic was correct, by inspecting our # logged joint velocities. if args.test: for time, qdot in zip(iiwa_velocities.sample_times(), iiwa_velocities.data().transpose()): # TODO(jwnimmer-tri) We should be able to do better than a 40 # rad/sec limit, but that's the best we can enforce for now. if qdot.max() > 0.1: print(f"ERROR: large qdot {qdot} at time {time}") sys.exit(1)
plant.world_frame(), plant.GetFrameByName("panda_link0", panda), X_AB=RigidTransform(np.array([0.0, 0.5, 0.0])) ) # Add a little example brick brick = parser.AddModelFromFile(brick_file, model_name="brick") # plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base_link")) # Add some bins bin_1 = parser.AddModelFromFile(bin_file, model_name="bin_1") plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("bin_base", bin_1)) bin_2 = parser.AddModelFromFile(bin_file, model_name="bin_2") plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("bin_base", bin_2), X_AB=RigidTransform(np.array([0.65, 0.5, 0.0]))) scene_graph.AddRenderer("renderer", MakeRenderEngineVtk(RenderEngineVtkParams())) DrakeVisualizer.AddToBuilder(builder, scene_graph) # Important to do tidying work plant.Finalize() # Gripper pose relative to object when in grasp p_GgraspO = [0, 0, 0.13] R_GgraspO = RotationMatrix.MakeXRotation(np.pi) X_GgraspO = RigidTransform(R_GgraspO, p_GgraspO) X_OGgrasp = X_GgraspO.inverse() # Pregrasp is negative z in the gripper frame X_GgraspGpregrasp = RigidTransform([0, 0.0, -0.08]) X_O = {"initial": RigidTransform([0.65, 0.5, 0.015]),
def test_decomposition_controller_like_workflow(self): """Tests subgraphs (post-finalize) for decomposition, with a scene-graph. Also shows a workflow of replacing joints / welding joints.""" builder = DiagramBuilder() # N.B. I (Eric) am using ManipulationStation because it's currently # the simplest way to get a complex scene in pydrake. station = ManipulationStation(time_step=0.001) station.SetupManipulationClassStation() station.Finalize() builder.AddSystem(station) plant = station.get_multibody_plant() scene_graph = station.get_scene_graph() iiwa = plant.GetModelInstanceByName("iiwa") wsg = plant.GetModelInstanceByName("gripper") if VISUALIZE: print("test_decomposition_controller_like_workflow") DrakeVisualizer.AddToBuilder(builder, station.GetOutputPort("query_object")) diagram = builder.Build() # Set the context with which things should be computed. d_context = diagram.CreateDefaultContext() context = plant.GetMyContextFromRoot(d_context) q_iiwa = [0.3, 0.7, 0.3, 0.6, 0.5, 0.6, 0.7] ndof = 7 q_wsg = [-0.03, 0.03] plant.SetPositions(context, iiwa, q_iiwa) plant.SetPositions(context, wsg, q_wsg) # Add copy of only the IIWA to a control diagram. control_builder = DiagramBuilder() control_plant = control_builder.AddSystem(MultibodyPlant(time_step=0)) # N.B. This has the same scene, but with all joints outside of the # IIWA frozen # TODO(eric.cousineau): Re-investigate weird "build_with_no_control" # behavior (with scene graph) with default conditions and time_step=0 # - see Anzu commit 2cf08cfc3. to_control = mut.add_plant_with_articulated_subset_to( plant_src=plant, scene_graph_src=scene_graph, articulated_models_src=[iiwa], context_src=context, plant_dest=control_plant) self.assertIsInstance(to_control, mut.MultibodyPlantElementsMap) control_iiwa = to_control.model_instances[iiwa] control_plant.Finalize() self.assertEqual(control_plant.num_positions(), plant.num_positions(iiwa)) kp = np.array([2000., 1500, 1500, 1500, 1500, 500, 500]) kd = np.sqrt(2 * kp) ki = np.zeros(7) controller = control_builder.AddSystem( InverseDynamicsController(robot=control_plant, kp=kp, ki=ki, kd=kd, has_reference_acceleration=False)) # N.B. Rather than use model instances for direct correspence, we could # use the mappings themselves within a custom system. control_builder.Connect( control_plant.get_state_output_port(control_iiwa), controller.get_input_port_estimated_state()) control_builder.Connect( controller.get_output_port_control(), control_plant.get_actuation_input_port(control_iiwa)) # Control to having the elbow slightly bent. q_iiwa_final = np.zeros(7) q_iiwa_final[3] = -np.pi / 2 t_start = 0. t_end = 1. nx = 2 * ndof def q_desired_interpolator(t: ContextTimeArg) -> VectorArg(nx): s = (t - t_start) / (t_end - t_start) ds = 1 / (t_end - t_start) q = q_iiwa + s * (q_iiwa_final - q_iiwa) v = ds * (q_iiwa_final - q_iiwa) x = np.hstack((q, v)) return x interpolator = control_builder.AddSystem( FunctionSystem(q_desired_interpolator)) control_builder.Connect(interpolator.get_output_port(0), controller.get_input_port_desired_state()) control_diagram = control_builder.Build() control_d_context = control_diagram.CreateDefaultContext() control_context = control_plant.GetMyContextFromRoot(control_d_context) to_control.copy_state(context, control_context) util.compare_frame_poses(plant, context, control_plant, control_context, "iiwa_link_0", "iiwa_link_7") util.compare_frame_poses(plant, context, control_plant, control_context, "body", "left_finger") from_control = to_control.inverse() def viz_monitor(control_d_context): # Simulate control, visualizing in original diagram. assert (control_context is control_plant.GetMyContextFromRoot(control_d_context)) from_control.copy_state(control_context, context) d_context.SetTime(control_d_context.get_time()) diagram.Publish(d_context) return EventStatus.DidNothing() simulator = Simulator(control_diagram, control_d_context) simulator.Initialize() if VISUALIZE: simulator.set_monitor(viz_monitor) simulator.set_target_realtime_rate(1.) simulator.AdvanceTo(t_end)
def connect_to_drake_visualizer(self): self._drake_viz = DrakeVisualizer.AddToBuilder(builder=self._builder, scene_graph=self._sg) return self._drake_viz
def main(): parser = argparse.ArgumentParser(description=__doc__) parser.add_argument( "--target_realtime_rate", type=float, default=1.0, help="Desired rate relative to real time. See documentation for " "Simulator::set_target_realtime_rate() for details.") parser.add_argument( "--duration", type=float, default=np.inf, help="Desired duration of the simulation in seconds.") parser.add_argument( "--hardware", action='store_true', help="Use the ManipulationStationHardwareInterface instead of an " "in-process simulation.") parser.add_argument( "--test", action='store_true', help="Disable opening the gui window for testing.") parser.add_argument( "--time_step", type=float, default=0.005, help="Time constant for the differential IK solver and first order" "low pass filter applied to the teleop commands") parser.add_argument( "--velocity_limit_factor", type=float, default=1.0, help="This value, typically between 0 and 1, further limits the " "iiwa14 joint velocities. It multiplies each of the seven " "pre-defined joint velocity limits. " "Note: The pre-defined velocity limits are specified by " "iiwa14_velocity_limits, found in this python file.") parser.add_argument( '--setup', type=str, default='manipulation_class', help="The manipulation station setup to simulate. ", choices=['manipulation_class', 'clutter_clearing']) parser.add_argument( '--schunk_collision_model', type=str, default='box', help="The Schunk collision model to use for simulation. ", choices=['box', 'box_plus_fingertip_spheres']) MeshcatVisualizer.add_argparse_argument(parser) args = parser.parse_args() if args.test: # Don't grab mouse focus during testing. # See: https://stackoverflow.com/a/52528832/7829525 os.environ["SDL_VIDEODRIVER"] = "dummy" builder = DiagramBuilder() if args.hardware: station = builder.AddSystem(ManipulationStationHardwareInterface()) station.Connect(wait_for_cameras=False) else: station = builder.AddSystem(ManipulationStation()) if args.schunk_collision_model == "box": schunk_model = SchunkCollisionModel.kBox elif args.schunk_collision_model == "box_plus_fingertip_spheres": schunk_model = SchunkCollisionModel.kBoxPlusFingertipSpheres # Initializes the chosen station type. if args.setup == 'manipulation_class': station.SetupManipulationClassStation( schunk_model=schunk_model) station.AddManipulandFromFile( ("drake/examples/manipulation_station/models/" "061_foam_brick.sdf"), RigidTransform(RotationMatrix.Identity(), [0.6, 0, 0])) elif args.setup == 'clutter_clearing': station.SetupClutterClearingStation( schunk_model=schunk_model) ycb_objects = CreateClutterClearingYcbObjectList() for model_file, X_WObject in ycb_objects: station.AddManipulandFromFile(model_file, X_WObject) station.Finalize() DrakeVisualizer.AddToBuilder(builder, station.GetOutputPort("query_object")) if args.meshcat: meshcat = ConnectMeshcatVisualizer( builder, output_port=station.GetOutputPort("geometry_query"), zmq_url=args.meshcat, open_browser=args.open_browser) if args.setup == 'planar': meshcat.set_planar_viewpoint() robot = station.get_controller_plant() params = DifferentialInverseKinematicsParameters(robot.num_positions(), robot.num_velocities()) params.set_timestep(args.time_step) # True velocity limits for the IIWA14 (in rad/s, rounded down to the first # decimal) iiwa14_velocity_limits = np.array([1.4, 1.4, 1.7, 1.3, 2.2, 2.3, 2.3]) # Stay within a small fraction of those limits for this teleop demo. factor = args.velocity_limit_factor params.set_joint_velocity_limits((-factor*iiwa14_velocity_limits, factor*iiwa14_velocity_limits)) differential_ik = builder.AddSystem(DifferentialIK( robot, robot.GetFrameByName("iiwa_link_7"), params, args.time_step)) builder.Connect(differential_ik.GetOutputPort("joint_position_desired"), station.GetInputPort("iiwa_position")) teleop = builder.AddSystem(DualShock4Teleop(initialize_joystick())) filter_ = builder.AddSystem( FirstOrderLowPassFilter(time_constant=args.time_step, size=6)) builder.Connect(teleop.get_output_port(0), filter_.get_input_port(0)) builder.Connect(filter_.get_output_port(0), differential_ik.GetInputPort("rpy_xyz_desired")) builder.Connect(teleop.GetOutputPort("position"), station.GetInputPort( "wsg_position")) builder.Connect(teleop.GetOutputPort("force_limit"), station.GetInputPort("wsg_force_limit")) diagram = builder.Build() simulator = Simulator(diagram) # This is important to avoid duplicate publishes to the hardware interface: simulator.set_publish_every_time_step(False) station_context = diagram.GetMutableSubsystemContext( station, simulator.get_mutable_context()) station.GetInputPort("iiwa_feedforward_torque").FixValue( station_context, np.zeros(7)) # If the diagram is only the hardware interface, then we must advance it a # little bit so that first LCM messages get processed. A simulated plant is # already publishing correct positions even without advancing, and indeed # we must not advance a simulated plant until the sliders and filters have # been initialized to match the plant. if args.hardware: simulator.AdvanceTo(1e-6) q0 = station.GetOutputPort("iiwa_position_measured").Eval(station_context) differential_ik.parameters.set_nominal_joint_position(q0) teleop.SetPose(differential_ik.ForwardKinematics(q0)) filter_.set_initial_output_value( diagram.GetMutableSubsystemContext( filter_, simulator.get_mutable_context()), teleop.get_output_port(0).Eval(diagram.GetMutableSubsystemContext( teleop, simulator.get_mutable_context()))) differential_ik.SetPositions(diagram.GetMutableSubsystemContext( differential_ik, simulator.get_mutable_context()), q0) simulator.set_target_realtime_rate(args.target_realtime_rate) print_instructions() simulator.AdvanceTo(args.duration)
def main(): parser = argparse.ArgumentParser(description=__doc__) parser.add_argument( "--target_realtime_rate", type=float, default=1.0, help="Desired rate relative to real time. See documentation for " "Simulator::set_target_realtime_rate() for details.") parser.add_argument("--duration", type=float, default=np.inf, help="Desired duration of the simulation in seconds.") parser.add_argument( "--hardware", action='store_true', help="Use the ManipulationStationHardwareInterface instead of an " "in-process simulation.") parser.add_argument("--test", action='store_true', help="Disable opening the gui window for testing.") parser.add_argument( '--setup', type=str, default='manipulation_class', help="The manipulation station setup to simulate. ", choices=['manipulation_class', 'clutter_clearing', 'planar']) parser.add_argument( "-w", "--open-window", dest="browser_new", action="store_const", const=1, default=None, help="Open the MeshCat display in a new browser window.") args = parser.parse_args() builder = DiagramBuilder() # NOTE: the meshcat instance is always created in order to create the # teleop controls (joint sliders and open/close gripper button). When # args.hardware is True, the meshcat server will *not* display robot # geometry, but it will contain the joint sliders and open/close gripper # button in the "Open Controls" tab in the top-right of the viewing server. meshcat = Meshcat() if args.hardware: # TODO(russt): Replace this hard-coded camera serial number with a # config file. camera_ids = ["805212060544"] station = builder.AddSystem( ManipulationStationHardwareInterface(camera_ids)) station.Connect(wait_for_cameras=False) else: station = builder.AddSystem(ManipulationStation()) # Initializes the chosen station type. if args.setup == 'manipulation_class': station.SetupManipulationClassStation() station.AddManipulandFromFile( "drake/examples/manipulation_station/models/" + "061_foam_brick.sdf", RigidTransform(RotationMatrix.Identity(), [0.6, 0, 0])) elif args.setup == 'clutter_clearing': station.SetupClutterClearingStation() ycb_objects = CreateClutterClearingYcbObjectList() for model_file, X_WObject in ycb_objects: station.AddManipulandFromFile(model_file, X_WObject) elif args.setup == 'planar': station.SetupPlanarIiwaStation() station.AddManipulandFromFile( "drake/examples/manipulation_station/models/" + "061_foam_brick.sdf", RigidTransform(RotationMatrix.Identity(), [0.6, 0, 0])) station.Finalize() geometry_query_port = station.GetOutputPort("geometry_query") DrakeVisualizer.AddToBuilder(builder, geometry_query_port) meshcat_visualizer = MeshcatVisualizerCpp.AddToBuilder( builder=builder, query_object_port=geometry_query_port, meshcat=meshcat) if args.setup == 'planar': meshcat.Set2dRenderMode() pyplot_visualizer = ConnectPlanarSceneGraphVisualizer( builder, station.get_scene_graph(), geometry_query_port) if args.browser_new is not None: url = meshcat.web_url() webbrowser.open(url=url, new=args.browser_new) teleop = builder.AddSystem( JointSliders(meshcat=meshcat, plant=station.get_controller_plant())) num_iiwa_joints = station.num_iiwa_joints() filter = builder.AddSystem( FirstOrderLowPassFilter(time_constant=2.0, size=num_iiwa_joints)) builder.Connect(teleop.get_output_port(0), filter.get_input_port(0)) builder.Connect(filter.get_output_port(0), station.GetInputPort("iiwa_position")) wsg_buttons = builder.AddSystem(SchunkWsgButtons(meshcat=meshcat)) builder.Connect(wsg_buttons.GetOutputPort("position"), station.GetInputPort("wsg_position")) builder.Connect(wsg_buttons.GetOutputPort("force_limit"), station.GetInputPort("wsg_force_limit")) # When in regression test mode, log our joint velocities to later check # that they were sufficiently quiet. if args.test: iiwa_velocities = builder.AddSystem(VectorLogSink(num_iiwa_joints)) builder.Connect(station.GetOutputPort("iiwa_velocity_estimated"), iiwa_velocities.get_input_port(0)) else: iiwa_velocities = None diagram = builder.Build() simulator = Simulator(diagram) # This is important to avoid duplicate publishes to the hardware interface: simulator.set_publish_every_time_step(False) station_context = diagram.GetMutableSubsystemContext( station, simulator.get_mutable_context()) station.GetInputPort("iiwa_feedforward_torque").FixValue( station_context, np.zeros(num_iiwa_joints)) # If the diagram is only the hardware interface, then we must advance it a # little bit so that first LCM messages get processed. A simulated plant is # already publishing correct positions even without advancing, and indeed # we must not advance a simulated plant until the sliders and filters have # been initialized to match the plant. if args.hardware: simulator.AdvanceTo(1e-6) # Eval the output port once to read the initial positions of the IIWA. q0 = station.GetOutputPort("iiwa_position_measured").Eval(station_context) teleop.SetPositions(q0) filter.set_initial_output_value( diagram.GetMutableSubsystemContext(filter, simulator.get_mutable_context()), q0) simulator.set_target_realtime_rate(args.target_realtime_rate) simulator.AdvanceTo(args.duration) # Ensure that our initialization logic was correct, by inspecting our # logged joint velocities. if args.test: iiwa_velocities_log = iiwa_velocities.FindLog(simulator.get_context()) for time, qdot in zip(iiwa_velocities_log.sample_times(), iiwa_velocities_log.data().transpose()): # TODO(jwnimmer-tri) We should be able to do better than a 40 # rad/sec limit, but that's the best we can enforce for now. if qdot.max() > 0.1: print(f"ERROR: large qdot {qdot} at time {time}") sys.exit(1)
def perform_iou_testing(model_file, test_specific_temp_directory, pose_directory): random_poses = {} # Read camera translation calculated and applied on gazebo # we read the random positions file as it contains everything: with open( test_specific_temp_directory + "/pics/" + pose_directory + "/poses.txt", "r") as datafile: for line in datafile: if line.startswith("Translation:"): line_split = line.split(" ") # we make the value negative since gazebo moved the robot # and in drakewe move the camera trans_x = float(line_split[1]) trans_y = float(line_split[2]) trans_z = float(line_split[3]) elif line.startswith("Scaling:"): line_split = line.split(" ") scaling = float(line_split[1]) else: line_split = line.split(" ") if line_split[1] == "nan": random_poses[line_split[0][:-1]] = 0 else: random_poses[line_split[0][:-1]] = float(line_split[1]) builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) parser = Parser(plant) model = make_parser(plant).AddModelFromFile(model_file) model_bodies = me.get_bodies(plant, {model}) frame_W = plant.world_frame() frame_B = model_bodies[0].body_frame() if len(plant.GetBodiesWeldedTo(plant.world_body())) < 2: plant.WeldFrames(frame_W, frame_B, X_PC=plant.GetDefaultFreeBodyPose(frame_B.body())) # Creating cameras: renderer_name = "renderer" scene_graph.AddRenderer(renderer_name, MakeRenderEngineVtk(RenderEngineVtkParams())) # N.B. These properties are chosen arbitrarily. depth_camera = DepthRenderCamera( RenderCameraCore( renderer_name, CameraInfo( width=960, height=540, focal_x=831.382036787, focal_y=831.382036787, center_x=480, center_y=270, ), ClippingRange(0.01, 10.0), RigidTransform(), ), DepthRange(0.01, 10.0), ) world_id = plant.GetBodyFrameIdOrThrow(plant.world_body().index()) # Creating perspective cam X_WB = xyz_rpy_deg( [ 1.6 / scaling + trans_x, -1.6 / scaling + trans_y, 1.2 / scaling + trans_z ], [-120, 0, 45], ) sensor_perspective = create_camera(builder, world_id, X_WB, depth_camera, scene_graph) # Creating top cam X_WB = xyz_rpy_deg([0 + trans_x, 0 + trans_y, 2.2 / scaling + trans_z], [-180, 0, -90]) sensor_top = create_camera(builder, world_id, X_WB, depth_camera, scene_graph) # Creating front cam X_WB = xyz_rpy_deg([2.2 / scaling + trans_x, 0 + trans_y, 0 + trans_z], [-90, 0, 90]) sensor_front = create_camera(builder, world_id, X_WB, depth_camera, scene_graph) # Creating side cam X_WB = xyz_rpy_deg([0 + trans_x, 2.2 / scaling + trans_y, 0 + trans_z], [-90, 0, 180]) sensor_side = create_camera(builder, world_id, X_WB, depth_camera, scene_graph) # Creating back cam X_WB = xyz_rpy_deg([-2.2 / scaling + trans_x, 0 + trans_y, 0 + trans_z], [-90, 0, -90]) sensor_back = create_camera(builder, world_id, X_WB, depth_camera, scene_graph) DrakeVisualizer.AddToBuilder(builder, scene_graph) # Remove gravity to avoid extra movements of the model when running the simulation plant.gravity_field().set_gravity_vector( np.array([0, 0, 0], dtype=np.float64)) # Switch off collisions to avoid problems with random positions collision_filter_manager = scene_graph.collision_filter_manager() model_inspector = scene_graph.model_inspector() geometry_ids = GeometrySet(model_inspector.GetAllGeometryIds()) collision_filter_manager.Apply( CollisionFilterDeclaration().ExcludeWithin(geometry_ids)) plant.Finalize() diagram = builder.Build() simulator = Simulator(diagram) simulator.Initialize() dofs = plant.num_actuated_dofs() if dofs != plant.num_positions(): raise ValueError( "Error on converted model: Num positions is not equal to num actuated dofs." ) if pose_directory == "random_pose": joint_positions = [0] * dofs for joint_name, pose in random_poses.items(): # check if NaN if pose != pose: pose = 0 # drake will add '_joint' when there's a name collision if plant.HasJointNamed(joint_name): joint = plant.GetJointByName(joint_name) else: joint = plant.GetJointByName(joint_name + "_joint") joint_positions[joint.position_start()] = pose sim_plant_context = plant.GetMyContextFromRoot( simulator.get_mutable_context()) plant.get_actuation_input_port(model).FixValue(sim_plant_context, np.zeros((dofs, 1))) plant.SetPositions(sim_plant_context, model, joint_positions) simulator.AdvanceTo(1) generate_images_and_iou(simulator, sensor_perspective, test_specific_temp_directory, pose_directory, 1) generate_images_and_iou(simulator, sensor_top, test_specific_temp_directory, pose_directory, 2) generate_images_and_iou(simulator, sensor_front, test_specific_temp_directory, pose_directory, 3) generate_images_and_iou(simulator, sensor_side, test_specific_temp_directory, pose_directory, 4) generate_images_and_iou(simulator, sensor_back, test_specific_temp_directory, pose_directory, 5)