def test_manipulation_station_hardware_interface(self): station = ManipulationStationHardwareInterface( camera_names=["123", "456"]) # Don't actually call Connect here, since it would block. station.get_controller_plant() self.assertEqual(len(station.get_camera_names()), 2) self.assertEqual(station.num_iiwa_joints(), 7)
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 test_manipulation_station_hardware_interface(self): station = ManipulationStationHardwareInterface( camera_ids=["123", "456"]) # Don't actually call Connect here, since it would block. station.get_controller_plant()
def build_station_real_world(builder, camera_ids): station = builder.AddSystem( ManipulationStationHardwareInterface(camera_ids)) station.Connect() return station
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.005, 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']) MeshcatVisualizer.add_argparse_argument(parser) args = parser.parse_args() if args.test: # Don't grab mouse focus during testing. grab_focus = False # See: https://stackoverflow.com/a/52528832/7829525 os.environ["SDL_VIDEODRIVER"] = "dummy" else: grab_focus = True builder = DiagramBuilder() if args.hardware: station = builder.AddSystem(ManipulationStationHardwareInterface()) 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) station.Finalize() ConnectDrakeVisualizer(builder, station.get_scene_graph(), station.GetOutputPort("pose_bundle")) if args.meshcat: meshcat = builder.AddSystem( MeshcatVisualizer(station.get_scene_graph(), zmq_url=args.meshcat)) builder.Connect(station.GetOutputPort("pose_bundle"), meshcat.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]) # 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(MouseKeyboardTeleop(grab_focus=grab_focus)) 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")) 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)) 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 GetBrickPose(config_file, viz=False): """Estimates the pose of the foam brick in a ManipulationStation setup. @param config_file str. The path to a camera configuration file. @param viz bool. If True, save point clouds to numpy arrays. @return An Isometry3 representing the pose of the brick. """ builder = DiagramBuilder() # create the PointCloudToPoseSystem pc_to_pose = builder.AddSystem( PointCloudToPoseSystem(config_file, viz, SegmentFoamBrick, GetFoamBrickPose)) # realsense serial numbers are >> 100 use_hardware = int(pc_to_pose.camera_configs["left_camera_serial"]) > 100 if use_hardware: camera_ids = [ pc_to_pose.camera_configs["left_camera_serial"], pc_to_pose.camera_configs["middle_camera_serial"], pc_to_pose.camera_configs["right_camera_serial"] ] station = builder.AddSystem( ManipulationStationHardwareInterface(camera_ids)) station.Connect() else: station = builder.AddSystem(ManipulationStation()) station.AddCupboard() object_file_path = \ "drake/examples/manipulation_station/models/061_foam_brick.sdf" brick = AddModelFromSdfFile(FindResourceOrThrow(object_file_path), station.get_mutable_multibody_plant(), station.get_mutable_scene_graph()) station.Finalize() # add systems to convert the depth images from ManipulationStation to # PointClouds left_camera_info = pc_to_pose.camera_configs["left_camera_info"] middle_camera_info = pc_to_pose.camera_configs["middle_camera_info"] right_camera_info = pc_to_pose.camera_configs["right_camera_info"] left_dut = builder.AddSystem( mut.DepthImageToPointCloud(camera_info=left_camera_info)) middle_dut = builder.AddSystem( mut.DepthImageToPointCloud(camera_info=middle_camera_info)) right_dut = builder.AddSystem( mut.DepthImageToPointCloud(camera_info=right_camera_info)) left_name_prefix = \ "camera_" + pc_to_pose.camera_configs["left_camera_serial"] middle_name_prefix = \ "camera_" + pc_to_pose.camera_configs["middle_camera_serial"] right_name_prefix = \ "camera_" + pc_to_pose.camera_configs["right_camera_serial"] # connect the depth images to the DepthImageToPointCloud converters builder.Connect(station.GetOutputPort(left_name_prefix + "_depth_image"), left_dut.depth_image_input_port()) builder.Connect(station.GetOutputPort(middle_name_prefix + "_depth_image"), middle_dut.depth_image_input_port()) builder.Connect(station.GetOutputPort(right_name_prefix + "_depth_image"), right_dut.depth_image_input_port()) # connect the rgb images to the PointCloudToPoseSystem builder.Connect(station.GetOutputPort(left_name_prefix + "_rgb_image"), pc_to_pose.GetInputPort("camera_left_rgb")) builder.Connect(station.GetOutputPort(middle_name_prefix + "_rgb_image"), pc_to_pose.GetInputPort("camera_middle_rgb")) builder.Connect(station.GetOutputPort(right_name_prefix + "_rgb_image"), pc_to_pose.GetInputPort("camera_right_rgb")) # connect the XYZ point clouds to PointCloudToPoseSystem builder.Connect(left_dut.point_cloud_output_port(), pc_to_pose.GetInputPort("left_point_cloud")) builder.Connect(middle_dut.point_cloud_output_port(), pc_to_pose.GetInputPort("middle_point_cloud")) builder.Connect(right_dut.point_cloud_output_port(), pc_to_pose.GetInputPort("right_point_cloud")) diagram = builder.Build() simulator = Simulator(diagram) if not use_hardware: X_WObject = Isometry3.Identity() X_WObject.set_translation([.6, 0, 0]) station_context = diagram.GetMutableSubsystemContext( station, simulator.get_mutable_context()) station.get_mutable_multibody_plant().tree().SetFreeBodyPoseOrThrow( station.get_mutable_multibody_plant().GetBodyByName( "base_link", brick), X_WObject, station.GetMutableSubsystemContext( station.get_mutable_multibody_plant(), station_context)) context = diagram.GetMutableSubsystemContext( pc_to_pose, simulator.get_mutable_context()) # returns the pose of the brick, of type Isometry3 return pc_to_pose.GetOutputPort("X_WObject").Eval(context)
def build_station_real_world(builder, camera_ids): station_hardware = ManipulationStationHardwareInterface(camera_ids) station_hardware.Connect() return station_hardware
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)
"--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.") MeshcatVisualizer.add_argparse_argument(parser) args = parser.parse_args() builder = DiagramBuilder() 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()) station.SetupDefaultStation() station.Finalize() ConnectDrakeVisualizer(builder, station.get_scene_graph(), station.GetOutputPort("pose_bundle")) if args.meshcat: meshcat = builder.AddSystem(MeshcatVisualizer( station.get_scene_graph(), zmq_url=args.meshcat, open_browser=args.open_browser)) builder.Connect(station.GetOutputPort("pose_bundle"), meshcat.get_input_port(0))
def RunRealRobot(self, plan_list, gripper_setpoint_list, extra_time=2.0): """ Constructs a Diagram that sends commands to ManipulationStationHardwareInterface. @param plan_list: A list of Plans to be executed. @param gripper_setpoint_list: A list of gripper setpoints. Each setpoint corresponds to a Plan. @param sim_duration: the duration of simulation in seconds. If unset, it is set to the sum of the durations of all plans in plan_list plus extra_time. @param extra_time: the amount of time for which commands are sent, in addition to the duration of all plans. @param is_plan_runner_diagram: True: use the diagram version of PlanRunner; False: use the leaf version of PlanRunner. @return: logs of robot configuration and torque, decoded from LCM messges sent by the robot's driver. Logs are SignalLogger systems, whose data can be accessed by SignalLogger.data(). """ builder = DiagramBuilder() camera_ids = ["805212060544"] station_hardware = ManipulationStationHardwareInterface(camera_ids) station_hardware.Connect(wait_for_cameras=False) builder.AddSystem(station_hardware) # Add plan runner. plan_runner = IiwaPlanRunner( iiwa_plans=plan_list, gripper_setpoint_list=gripper_setpoint_list, print_period=np.inf) iiwa_position_command_log, iiwa_position_measured_log, \ iiwa_external_torque_log, iiwa_velocity_estimated_log = \ self.ConnectPortsAndAddLoggers( builder, station_hardware, plan_runner) # build diagram diagram = builder.Build() # RenderSystemWithGraphviz(diagram) # construct simulator simulator = Simulator(diagram) self.simulator = simulator simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(False) t_plan = GetPlanStartingTimes(plan_list) sim_duration = t_plan[-1] + extra_time print("simulation duration", sim_duration) print("plan starting times\n", t_plan) # set initial command to be the same as current robot joint angles. q0 = self.GetCurrentJointAngles() plan_runner_context = \ diagram.GetMutableSubsystemContext( plan_runner, simulator.get_mutable_context()) state = plan_runner_context.get_mutable_discrete_state_vector().get_mutable_value() state[:self.nq] = q0 simulator.Initialize() simulator.AdvanceTo(sim_duration) return (iiwa_position_command_log, iiwa_position_measured_log, iiwa_velocity_estimated_log, iiwa_external_torque_log, t_plan)
def RunRealRobot(self, plans_list, gripper_setpoint_list): """ Constructs a Diagram that sends commands to ManipulationStationHardwareInterface. @param plans_list: A list of Plans to be executed. @param gripper_setpoint_list: A list of gripper setpoints. Each setpoint corresponds to a Plan. @return: logs of robot configuration and torque, decoded from LCM messges sent by the robot's driver. Logs are SignalLogger systems, whose data can be accessed by SignalLogger.data(). """ builder = DiagramBuilder() camera_ids = ["805212060544"] station_hardware = ManipulationStationHardwareInterface(camera_ids) station_hardware.Connect(wait_for_cameras=False) builder.AddSystem(station_hardware) # Add plan runner # Add plan runner. plan_runner = ManipStationPlanRunner( station=self.station, kuka_plans=plans_list, gripper_setpoint_list=gripper_setpoint_list) builder.AddSystem(plan_runner) builder.Connect(plan_runner.hand_setpoint_output_port, station_hardware.GetInputPort("wsg_position")) builder.Connect(plan_runner.gripper_force_limit_output_port, station_hardware.GetInputPort("wsg_force_limit")) demux = builder.AddSystem(Demultiplexer(14, 7)) builder.Connect( plan_runner.GetOutputPort("iiwa_position_and_torque_command"), demux.get_input_port(0)) builder.Connect(demux.get_output_port(0), station_hardware.GetInputPort("iiwa_position")) builder.Connect( demux.get_output_port(1), station_hardware.GetInputPort("iiwa_feedforward_torque")) builder.Connect( station_hardware.GetOutputPort("iiwa_position_measured"), plan_runner.iiwa_position_input_port) builder.Connect( station_hardware.GetOutputPort("iiwa_velocity_estimated"), plan_runner.iiwa_velocity_input_port) # Add logger iiwa_position_command_log = LogOutput(demux.get_output_port(0), builder) iiwa_position_command_log._DeclarePeriodicPublish(0.005) iiwa_position_measured_log = LogOutput( station_hardware.GetOutputPort("iiwa_position_measured"), builder) iiwa_position_measured_log._DeclarePeriodicPublish(0.005) iiwa_external_torque_log = LogOutput( station_hardware.GetOutputPort("iiwa_torque_external"), builder) iiwa_external_torque_log._DeclarePeriodicPublish(0.005) # build diagram diagram = builder.Build() # RenderSystemWithGraphviz(diagram) # construct simulator simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(False) sim_duration = 0. for plan in plans_list: sim_duration += plan.get_duration() * 1.1 print "sending trajectories in 2 seconds..." time.sleep(1.0) print "sending trajectories in 1 second..." time.sleep(1.0) print "sending trajectories now!" simulator.StepTo(sim_duration) return iiwa_position_command_log, \ iiwa_position_measured_log, iiwa_external_torque_log
class ManipulationStationSimulator: def __init__(self, time_step, object_file_path, object_base_link_name, is_hardware=False): self.object_base_link_name = object_base_link_name self.time_step = time_step self.is_hardware = is_hardware # Finalize manipulation station by adding manipuland. self.station = ManipulationStation(self.time_step) self.station.AddCupboard() self.plant = self.station.get_mutable_multibody_plant() self.object = AddModelFromSdfFile( file_name=object_file_path, model_name="object", plant=self.station.get_mutable_multibody_plant(), scene_graph=self.station.get_mutable_scene_graph()) self.station.Finalize() def RunSimulation(self, plans_list, gripper_setpoint_list, extra_time=0, real_time_rate=1.0, q0_kuka=np.zeros(7)): ''' Constructs a Diagram that sends commands to ManipulationStation. :param plans_list: :param gripper_setpoint_list: :param extra_time: :param real_time_rate: :param q0_kuka: :return: ''' builder = DiagramBuilder() builder.AddSystem(self.station) # Add plan runner plan_runner = KukaPlanRunner(self.plant) builder.AddSystem(plan_runner) builder.Connect(plan_runner.get_output_port(0), self.station.GetInputPort("iiwa_position")) # Add state machine. state_machine = ManipStateMachine( plant=self.plant, kuka_plans=plans_list, gripper_setpoint_list=gripper_setpoint_list) builder.AddSystem(state_machine) builder.Connect(state_machine.kuka_plan_output_port, plan_runner.plan_input_port) builder.Connect(state_machine.hand_setpoint_output_port, self.station.GetInputPort("wsg_position")) builder.Connect(state_machine.gripper_force_limit_output_port, self.station.GetInputPort("wsg_force_limit")) builder.Connect(self.station.GetOutputPort("iiwa_position_measured"), state_machine.iiwa_position_input_port) # Add meshcat visualizer from underactuated.meshcat_visualizer import MeshcatVisualizer scene_graph = self.station.get_mutable_scene_graph() viz = MeshcatVisualizer(scene_graph) builder.AddSystem(viz) builder.Connect(self.station.GetOutputPort("pose_bundle"), viz.get_input_port(0)) # Add logger iiwa_position_command_log = builder.AddSystem( SignalLogger(self.station.GetInputPort("iiwa_position").size())) iiwa_position_command_log._DeclarePeriodicPublish(0.005) builder.Connect(plan_runner.get_output_port(0), iiwa_position_command_log.get_input_port(0)) # build diagram diagram = builder.Build() viz.load() time.sleep(2.0) RenderSystemWithGraphviz(diagram) # construct simulator simulator = Simulator(diagram) context = diagram.GetMutableSubsystemContext( self.station, simulator.get_mutable_context()) # set initial state of the robot self.station.SetIiwaPosition(q0_kuka, context) self.station.SetIiwaVelocity(np.zeros(7), context) self.station.SetWsgState(0.05, 0, context) # set initial hinge angles of the cupboard. left_hinge_joint = self.plant.GetJointByName("left_door_hinge") left_hinge_joint.set_angle( context=self.station.GetMutableSubsystemContext( self.plant, context), angle=-np.pi / 2) right_hinge_joint = self.plant.GetJointByName("right_door_hinge") right_hinge_joint.set_angle( context=self.station.GetMutableSubsystemContext( self.plant, context), angle=np.pi / 2) # set initial pose of the object X_WObject = Isometry3.Identity() X_WObject.set_translation([.6, 0, 0]) self.plant.tree().SetFreeBodyPoseOrThrow( self.plant.GetBodyByName(self.object_base_link_name, self.object), X_WObject, self.station.GetMutableSubsystemContext(self.plant, context)) # fix feedforward torque input to 0. context.FixInputPort( self.station.GetInputPort("iiwa_feedforward_torque").get_index(), np.zeros(7)) simulator.set_publish_every_time_step(False) simulator.set_target_realtime_rate(real_time_rate) simulator.Initialize() sim_duration = 0. for plan in plans_list: sim_duration += plan.get_duration() * 1.1 sim_duration += extra_time print "simulation duration", sim_duration simulator.StepTo(sim_duration) return iiwa_position_command_log def RunRealRobot(self, plans_list, gripper_setpoint_list): ''' Constructs a Diagram that sends commands to ManipulationStationHardwareInterface. :param plans_list: :param gripper_setpoint_list: :param extra_time: :param real_time_rate: :param q0_kuka: :return: ''' from pydrake.examples.manipulation_station import ManipulationStationHardwareInterface builder = DiagramBuilder() self.station_hardware = ManipulationStationHardwareInterface() builder.AddSystem(self.station_hardware) # Add plan runner plan_runner = KukaPlanRunner(self.plant) builder.AddSystem(plan_runner) builder.Connect(plan_runner.get_output_port(0), self.station_hardware.GetInputPort("iiwa_position")) # Add state machine. state_machine = ManipStateMachine( plant=self.plant, kuka_plans=plans_list, gripper_setpoint_list=gripper_setpoint_list) builder.AddSystem(state_machine) builder.Connect(state_machine.kuka_plan_output_port, plan_runner.plan_input_port) builder.Connect(state_machine.hand_setpoint_output_port, self.station_hardware.GetInputPort("wsg_position")) builder.Connect(state_machine.gripper_force_limit_output_port, self.station_hardware.GetInputPort("wsg_force_limit")) builder.Connect( self.station_hardware.GetOutputPort("iiwa_position_measured"), state_machine.iiwa_position_input_port) # Add logger iiwa_position_command_log = builder.AddSystem( SignalLogger( self.station_hardware.GetInputPort("iiwa_position").size())) builder.Connect(plan_runner.get_output_port(0), iiwa_position_command_log.get_input_port(0)) # build diagram diagram = builder.Build() RenderSystemWithGraphviz(diagram) # construct simulator simulator = Simulator(diagram) context = diagram.GetMutableSubsystemContext( self.station_hardware, simulator.get_mutable_context()) context.FixInputPort( self.station.GetInputPort("iiwa_feedforward_torque").get_index(), np.zeros(7)) simulator.set_target_realtime_rate(1.0) simulator.Initialize() # simulator.set_publish_at_initialization(False) sim_duration = 0. for plan in plans_list: sim_duration += plan.get_duration() * 1.1 print "sending trajectories in 2 seconds..." time.sleep(1.0) print "sending trajectories in 1 second..." time.sleep(1.0) print "sending trajectories now!" simulator.StepTo(sim_duration) return iiwa_position_command_log
def RunRealRobot(self, plans_list, gripper_setpoint_list): ''' Constructs a Diagram that sends commands to ManipulationStationHardwareInterface. :param plans_list: :param gripper_setpoint_list: :param extra_time: :param real_time_rate: :param q0_kuka: :return: ''' from pydrake.examples.manipulation_station import ManipulationStationHardwareInterface builder = DiagramBuilder() self.station_hardware = ManipulationStationHardwareInterface() builder.AddSystem(self.station_hardware) # Add plan runner plan_runner = KukaPlanRunner(self.plant) builder.AddSystem(plan_runner) builder.Connect(plan_runner.get_output_port(0), self.station_hardware.GetInputPort("iiwa_position")) # Add state machine. state_machine = ManipStateMachine( plant=self.plant, kuka_plans=plans_list, gripper_setpoint_list=gripper_setpoint_list) builder.AddSystem(state_machine) builder.Connect(state_machine.kuka_plan_output_port, plan_runner.plan_input_port) builder.Connect(state_machine.hand_setpoint_output_port, self.station_hardware.GetInputPort("wsg_position")) builder.Connect(state_machine.gripper_force_limit_output_port, self.station_hardware.GetInputPort("wsg_force_limit")) builder.Connect( self.station_hardware.GetOutputPort("iiwa_position_measured"), state_machine.iiwa_position_input_port) # Add logger iiwa_position_command_log = builder.AddSystem( SignalLogger( self.station_hardware.GetInputPort("iiwa_position").size())) builder.Connect(plan_runner.get_output_port(0), iiwa_position_command_log.get_input_port(0)) # build diagram diagram = builder.Build() RenderSystemWithGraphviz(diagram) # construct simulator simulator = Simulator(diagram) context = diagram.GetMutableSubsystemContext( self.station_hardware, simulator.get_mutable_context()) context.FixInputPort( self.station.GetInputPort("iiwa_feedforward_torque").get_index(), np.zeros(7)) simulator.set_target_realtime_rate(1.0) simulator.Initialize() # simulator.set_publish_at_initialization(False) sim_duration = 0. for plan in plans_list: sim_duration += plan.get_duration() * 1.1 print "sending trajectories in 2 seconds..." time.sleep(1.0) print "sending trajectories in 1 second..." time.sleep(1.0) print "sending trajectories now!" simulator.StepTo(sim_duration) return iiwa_position_command_log
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)
def RunRealRobot( self, plan_list, gripper_setpoint_list, sim_duration=None, extra_time=2.0, is_plan_runner_diagram=False, ): """ Constructs a Diagram that sends commands to ManipulationStationHardwareInterface. @param plan_list: A list of Plans to be executed. @param gripper_setpoint_list: A list of gripper setpoints. Each setpoint corresponds to a Plan. @param sim_duration: the duration of simulation in seconds. If unset, it is set to the sum of the durations of all plans in plan_list plus extra_time. @param extra_time: the amount of time for which commands are sent, in addition to the duration of all plans. @param is_plan_runner_diagram: True: use the diagram version of PlanRunner; False: use the leaf version of PlanRunner. @return: logs of robot configuration and torque, decoded from LCM messges sent by the robot's driver. Logs are SignalLogger systems, whose data can be accessed by SignalLogger.data(). """ builder = DiagramBuilder() camera_ids = ["805212060544"] station_hardware = ManipulationStationHardwareInterface(camera_ids) station_hardware.Connect(wait_for_cameras=False) builder.AddSystem(station_hardware) # Add plan runner. if is_plan_runner_diagram: plan_runner, duration_multiplier = CreateManipStationPlanRunnerDiagram( kuka_plans=plan_list, gripper_setpoint_list=gripper_setpoint_list, print_period=0, ) else: plan_runner = ManipStationPlanRunner( kuka_plans=plan_list, gripper_setpoint_list=gripper_setpoint_list, print_period=0, ) duration_multiplier = plan_runner.kPlanDurationMultiplier builder.AddSystem(plan_runner) builder.Connect(plan_runner.GetOutputPort("gripper_setpoint"), station_hardware.GetInputPort("wsg_position")) builder.Connect(plan_runner.GetOutputPort("force_limit"), station_hardware.GetInputPort("wsg_force_limit")) builder.Connect(plan_runner.GetOutputPort("iiwa_position_command"), station_hardware.GetInputPort("iiwa_position")) builder.Connect( plan_runner.GetOutputPort("iiwa_torque_command"), station_hardware.GetInputPort("iiwa_feedforward_torque")) builder.Connect( station_hardware.GetOutputPort("iiwa_position_measured"), plan_runner.GetInputPort("iiwa_position")) builder.Connect( station_hardware.GetOutputPort("iiwa_velocity_estimated"), plan_runner.GetInputPort("iiwa_velocity")) builder.Connect(station_hardware.GetOutputPort("iiwa_torque_external"), plan_runner.GetInputPort("iiwa_torque_external")) # Add logger iiwa_position_command_log = LogOutput( plan_runner.GetOutputPort("iiwa_position_command"), builder) iiwa_position_command_log._DeclarePeriodicPublish(0.005) iiwa_position_measured_log = LogOutput( station_hardware.GetOutputPort("iiwa_position_measured"), builder) iiwa_position_measured_log._DeclarePeriodicPublish(0.005) iiwa_velocity_estimated_log = LogOutput( station_hardware.GetOutputPort("iiwa_velocity_estimated"), builder) iiwa_velocity_estimated_log._DeclarePeriodicPublish(0.005) iiwa_external_torque_log = LogOutput( station_hardware.GetOutputPort("iiwa_torque_external"), builder) iiwa_external_torque_log._DeclarePeriodicPublish(0.005) # build diagram diagram = builder.Build() # RenderSystemWithGraphviz(diagram) # construct simulator simulator = Simulator(diagram) self.simulator = simulator simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(False) t_plan = GetPlanStartingTimes(plan_list, duration_multiplier) if sim_duration is None: sim_duration = t_plan[-1] + extra_time print "simulation duration", sim_duration print "plan starting times\n", t_plan print "sending trajectories in 2 seconds..." time.sleep(1.0) print "sending trajectories in 1 second..." time.sleep(1.0) print "sending trajectories now!" simulator.Initialize() self.SetInitialPlanRunnerState(plan_runner, simulator, diagram) simulator.StepTo(sim_duration) return iiwa_position_command_log, iiwa_position_measured_log, \ iiwa_velocity_estimated_log, iiwa_external_torque_log, t_plan
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.") 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()) station.SetupDefaultStation() parser = Parser(station.get_mutable_multibody_plant(), station.get_mutable_scene_graph()) object = parser.AddModelFromFile( FindResourceOrThrow( "drake/examples/manipulation_station/models/061_foam_brick.sdf"), "object") station.Finalize() ConnectDrakeVisualizer(builder, station.get_scene_graph(), station.GetOutputPort("pose_bundle")) if args.meshcat:
def test_manipulation_station_hardware_interface(self): station = ManipulationStationHardwareInterface( camera_names=["123", "456"]) # Don't actually call Connect here, since it would block. station.get_controller_plant() self.assertEqual(len(station.get_camera_names()), 2)
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.") args = parser.parse_args() builder = DiagramBuilder() 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()) station.AddCupboard() object = AddModelFromSdfFile( FindResourceOrThrow( "drake/examples/manipulation_station/models/061_foam_brick.sdf"), "object", station.get_mutable_multibody_plant(), station.get_mutable_scene_graph()) station.Finalize() ConnectDrakeVisualizer(builder, station.get_scene_graph(), station.GetOutputPort("pose_bundle")) teleop = builder.AddSystem(
def RunRealRobot(self, plans_list, gripper_setpoint_list): ''' Constructs a Diagram that sends commands to ManipulationStationHardwareInterface. :param plans_list: :param gripper_setpoint_list: :param extra_time: :param real_time_rate: :param q0_kuka: :return: ''' builder = DiagramBuilder() camera_ids = ["805212060544"] station_hardware = ManipulationStationHardwareInterface(camera_ids) station_hardware.Connect(wait_for_cameras=False) builder.AddSystem(station_hardware) # Add plan runner # Add plan runner. plan_runner = ManipStationPlanRunner( station=self.station, kuka_plans=plans_list, gripper_setpoint_list=gripper_setpoint_list) builder.AddSystem(plan_runner) builder.Connect(plan_runner.hand_setpoint_output_port, station_hardware.GetInputPort("wsg_position")) builder.Connect(plan_runner.gripper_force_limit_output_port, station_hardware.GetInputPort("wsg_force_limit")) demux = builder.AddSystem(Demultiplexer(14, 7)) builder.Connect( plan_runner.GetOutputPort("iiwa_position_and_torque_command"), demux.get_input_port(0)) builder.Connect(demux.get_output_port(0), station_hardware.GetInputPort("iiwa_position")) builder.Connect( demux.get_output_port(1), station_hardware.GetInputPort("iiwa_feedforward_torque")) builder.Connect( station_hardware.GetOutputPort("iiwa_position_measured"), plan_runner.iiwa_position_input_port) builder.Connect( station_hardware.GetOutputPort("iiwa_velocity_estimated"), plan_runner.iiwa_velocity_input_port) # Add logger iiwa_position_measured_log = LogOutput( station_hardware.GetOutputPort("iiwa_position_measured"), builder) iiwa_position_measured_log._DeclarePeriodicPublish(0.005) iiwa_external_torque_log = LogOutput( station_hardware.GetOutputPort("iiwa_torque_external"), builder) iiwa_external_torque_log._DeclarePeriodicPublish(0.005) wsg_state_log = LogOutput( station_hardware.GetOutputPort("wsg_state_measured"), builder) wsg_state_log._DecalrePeriodicPublish(0.1) wsg_command_log = LogOutput(plan_runner.hand_setpoint_output_port, builder) wsg_command_log._DeclarePeriodicPublish(0.1) # build diagram diagram = builder.Build() RenderSystemWithGraphviz(diagram) # construct simulator simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(False) sim_duration = 0. for plan in plans_list: sim_duration += plan.get_duration() * 1.1 print "sending trajectories in 2 seconds..." time.sleep(1.0) print "sending trajectories in 1 second..." time.sleep(1.0) print "sending trajectories now!" simulator.StepTo(sim_duration) return iiwa_position_measured_log, iiwa_external_torque_log, wsg_state_log, wsg_command_log