def runPendulumExample(args): builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder) parser = Parser(plant) parser.AddModelFromFile(FindResource("pendulum/pendulum.urdf")) plant.Finalize() pose_bundle_output_port = scene_graph.get_pose_bundle_output_port() Tview = np.array([[1., 0., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]], dtype=np.float64) visualizer = builder.AddSystem( PlanarSceneGraphVisualizer(scene_graph, Tview=Tview, xlim=[-1.2, 1.2], ylim=[-1.2, 1.2])) builder.Connect(pose_bundle_output_port, visualizer.get_input_port(0)) diagram = builder.Build() simulator = Simulator(diagram) simulator.Initialize() simulator.set_target_realtime_rate(1.0) # Fix the input port to zero. plant_context = diagram.GetMutableSubsystemContext( plant, simulator.get_mutable_context()) plant_context.FixInputPort(plant.get_actuation_input_port().get_index(), np.zeros(plant.num_actuators())) plant_context.SetContinuousState([0.5, 0.1]) simulator.StepTo(args.duration)
def Simulate2dRamone(x0, duration, desired_goal = 0.0, print_period = 0.0): builder = DiagramBuilder() tree = RigidBodyTree() AddModelInstanceFromUrdfFile("ramone_act.urdf", FloatingBaseType.kRollPitchYaw, None, tree) plant = builder.AddSystem(RigidBodyPlant(tree)) controller = builder.AddSystem( Ramone2dController(tree, desired_goal=desired_goal, print_period=print_period)) builder.Connect(plant.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), plant.get_input_port(0)) state_log = builder.AddSystem(SignalLogger(plant.get_num_states())) builder.Connect(plant.get_output_port(0), state_log.get_input_port(0)) diagram = builder.Build() simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(True) simulator.get_mutable_context().set_accuracy(1e-4) state = simulator.get_mutable_context().get_mutable_continuous_state_vector() state.SetFromVector(x0) simulator.StepTo(duration) return tree, controller, state_log, plant
def playbackMotion(data1, data2, data3, data4, times): data = np.concatenate((data2, data1, data4, data3), axis=0) tree = RigidBodyTree( FindResource( os.path.dirname(os.path.realpath(__file__)) + "/block_pusher2.urdf"), FloatingBaseType.kFixed) # Set up a block diagram with the robot (dynamics), the controller, and a # visualization block. builder = DiagramBuilder() robot = builder.AddSystem(Player(data, times)) Tview = np.array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 0., 1.]], dtype=np.float64) visualizer = builder.AddSystem( PlanarRigidBodyVisualizer(tree, Tview, xlim=[-2.8, 4.8], ylim=[-2.8, 10])) #print(robot.get_output_port(0).size()) builder.Connect(robot.get_output_port(0), visualizer.get_input_port(0)) logger = builder.AddSystem( SignalLogger(tree.get_num_positions() + tree.get_num_velocities())) builder.Connect(robot.get_output_port(0), logger.get_input_port(0)) diagram = builder.Build() # Set up a simulator to run this diagram simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(True) # Simulate for 10 seconds simulator.StepTo(times[-1] + 0.5)
def RunSimulation(quadrotor_plant, control_law, x0=np.random.random((8, 1)), duration=30, control_period=0.0333, print_period=1.0, simulation_period=0.0333): quadrotor_controller = QuadrotorController(control_law, control_period=control_period, print_period=print_period) # Create a simple block diagram containing the plant in feedback # with the controller. builder = DiagramBuilder() # The last pendulum plant we made is now owned by a deleted # system, so easiest path is for us to make a new one. plant = builder.AddSystem( QuadrotorPendulum(mb=quadrotor_plant.mb, lb=quadrotor_plant.lb, m1=quadrotor_plant.m1, l1=quadrotor_plant.l1, g=quadrotor_plant.g, input_max=quadrotor_plant.input_max)) controller = builder.AddSystem(quadrotor_controller) builder.Connect(plant.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), plant.get_input_port(0)) # Create a logger to capture the simulation of our plant input_log = builder.AddSystem(SignalLogger(2)) input_log._DeclarePeriodicPublish(control_period, 0.0) builder.Connect(controller.get_output_port(0), input_log.get_input_port(0)) state_log = builder.AddSystem(SignalLogger(8)) state_log._DeclarePeriodicPublish(control_period, 0.0) builder.Connect(plant.get_output_port(0), state_log.get_input_port(0)) diagram = builder.Build() # Set the initial conditions for the simulation. context = diagram.CreateDefaultContext() state = context.get_mutable_continuous_state_vector() state.SetFromVector(x0) # Create the simulator. simulator = Simulator(diagram, context) simulator.Initialize() simulator.set_publish_every_time_step(True) simulator.get_integrator().set_fixed_step_mode(True) simulator.get_integrator().set_maximum_step_size(control_period) # Simulate for the requested duration. simulator.StepTo(duration) return input_log, state_log
def simulateRobot(time, B, v_command): tree = RigidBodyTree( FindResource( os.path.dirname(os.path.realpath(__file__)) + "/block_pusher2.urdf"), FloatingBaseType.kFixed) # Set up a block diagram with the robot (dynamics), the controller, and a # visualization block. builder = DiagramBuilder() robot = builder.AddSystem(RigidBodyPlant(tree)) controller = builder.AddSystem(DController(tree, B, v_command)) builder.Connect(robot.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), robot.get_input_port(0)) Tview = np.array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 0., 1.]], dtype=np.float64) visualizer = builder.AddSystem( PlanarRigidBodyVisualizer(tree, Tview, xlim=[-2.8, 4.8], ylim=[-2.8, 10])) builder.Connect(robot.get_output_port(0), visualizer.get_input_port(0)) logger = builder.AddSystem( SignalLogger(tree.get_num_positions() + tree.get_num_velocities())) builder.Connect(robot.get_output_port(0), logger.get_input_port(0)) diagram = builder.Build() # Set up a simulator to run this diagram simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(True) # Set the initial conditions context = simulator.get_mutable_context() state = context.get_mutable_continuous_state_vector() start1 = 3 * np.pi / 16 start2 = 15 * np.pi / 16 #np.pi/6 - eps, 2*np.pi/3 + eps, -np.pi/6 + eps, -2*np.pi/3 - eps, np.pi/6 - eps, 2*np.pi/3 + eps, -np.pi/6 + eps, -2*np.pi/3 - eps state.SetFromVector( (start1, start2, -start1, -start2, np.pi + start1, start2, np.pi - start1, -start2, 1, 1, 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.)) # (theta1, theta2, theta1dot, theta2dot) # Simulate for 10 seconds simulator.StepTo(time) #import pdb; pdb.set_trace() return (logger.data()[8:11, :], logger.data()[:8, :], logger.data()[19:22, :], logger.data()[11:19, :], logger.sample_times())
def RunSimulation(pendulum_plant, control_law, x0=np.random.random((4, 1)), duration=30): pendulum_controller = PendulumController(control_law) # Create a simple block diagram containing the plant in feedback # with the controller. builder = DiagramBuilder() # The last pendulum plant we made is now owned by a deleted # system, so easiest path is for us to make a new one. plant = builder.AddSystem( InertialWheelPendulum(m1=pendulum_plant.m1, l1=pendulum_plant.l1, m2=pendulum_plant.m2, l2=pendulum_plant.l2, r=pendulum_plant.r, g=pendulum_plant.g, input_max=pendulum_plant.input_max)) controller = builder.AddSystem(pendulum_controller) builder.Connect(plant.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), plant.get_input_port(0)) # Create a logger to capture the simulation of our plant input_log = builder.AddSystem(SignalLogger(1)) input_log._DeclarePeriodicPublish(0.033333, 0.0) builder.Connect(controller.get_output_port(0), input_log.get_input_port(0)) state_log = builder.AddSystem(SignalLogger(4)) state_log._DeclarePeriodicPublish(0.033333, 0.0) builder.Connect(plant.get_output_port(0), state_log.get_input_port(0)) diagram = builder.Build() # Set the initial conditions for the simulation. context = diagram.CreateDefaultContext() state = context.get_mutable_continuous_state_vector() state.SetFromVector(x0) # Create the simulator. simulator = Simulator(diagram, context) simulator.Initialize() simulator.set_publish_every_time_step(False) simulator.get_integrator().set_fixed_step_mode(True) simulator.get_integrator().set_maximum_step_size(0.005) # Simulate for the requested duration. simulator.StepTo(duration) return input_log, state_log
def Simulate2dBallAndBeam(x0, duration): builder = DiagramBuilder() # Load in the ball and beam from a description file. tree = RigidBodyTree() AddModelInstancesFromSdfString( open("ball_and_beam.sdf", 'r').read(), FloatingBaseType.kFixed, None, tree) # A RigidBodyPlant wraps a RigidBodyTree to allow # forward dynamical simulation. plant = builder.AddSystem(RigidBodyPlant(tree)) # Spawn a controller and hook it up controller = builder.AddSystem(BallAndBeam2dController(tree)) builder.Connect(plant.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), plant.get_input_port(0)) # Create a logger to log at 30hz state_log = builder.AddSystem(SignalLogger(plant.get_num_states())) state_log._DeclarePeriodicPublish(0.0333, 0.0) # 30hz logging builder.Connect(plant.get_output_port(0), state_log.get_input_port(0)) # Create a simulator diagram = builder.Build() simulator = Simulator(diagram) # Don't limit realtime rate for this sim, since we # produce a video to render it after simulating the whole thing. #simulator.set_target_realtime_rate(100.0) simulator.set_publish_every_time_step(False) # Force the simulator to use a fixed-step integrator, # which is much faster for this stiff system. (Due to the # spring-model of collision, the default variable-timestep # integrator will take very short steps. I've chosen the step # size here to be fast while still being stable in most situations.) integrator = simulator.get_mutable_integrator() integrator.set_fixed_step_mode(True) integrator.set_maximum_step_size(0.001) # Set the initial state state = simulator.get_mutable_context( ).get_mutable_continuous_state_vector() state.SetFromVector(x0) # Simulate! simulator.StepTo(duration) return tree, controller, state_log
def simulate_acrobot(): builder = DiagramBuilder() acrobot = builder.AddSystem(AcrobotPlant()) saturation = builder.AddSystem(Saturation(min_value=[-10], max_value=[10])) builder.Connect(saturation.get_output_port(0), acrobot.get_input_port(0)) wrapangles = WrapToSystem(4) wrapangles.set_interval(0, 0, 2. * math.pi) wrapangles.set_interval(1, -math.pi, math.pi) wrapto = builder.AddSystem(wrapangles) builder.Connect(acrobot.get_output_port(0), wrapto.get_input_port(0)) controller = builder.AddSystem(BalancingLQR()) builder.Connect(wrapto.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), saturation.get_input_port(0)) tree = RigidBodyTree(FindResource("acrobot/acrobot.urdf"), FloatingBaseType.kFixed) visualizer = builder.AddSystem( PlanarRigidBodyVisualizer(tree, xlim=[-4., 4.], ylim=[-4., 4.])) builder.Connect(acrobot.get_output_port(0), visualizer.get_input_port(0)) diagram = builder.Build() simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(False) context = simulator.get_mutable_context() state = context.get_mutable_continuous_state_vector() parser = argparse.ArgumentParser() parser.add_argument("-N", "--trials", type=int, help="Number of trials to run.", default=5) parser.add_argument("-T", "--duration", type=float, help="Duration to run each sim.", default=4.0) args = parser.parse_args() print(AcrobotPlant) for i in range(args.trials): context.set_time(0.) state.SetFromVector(UprightState().CopyToVector() + 0.05 * np.random.randn(4, )) simulator.StepTo(args.duration)
def RunSimulation(self, real_time_rate=1.0): ''' Here we test using the NNSystem in a Simulator to drive an acrobot. ''' sdf_file = "assets/acrobot.sdf" urdf_file = "assets/acrobot.urdf" builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder) parser = Parser(plant=plant, scene_graph=scene_graph) parser.AddModelFromFile(sdf_file) plant.Finalize(scene_graph) # Add nn_system = NNSystem(self.pytorch_nn_object) builder.AddSystem(nn_system) # NN -> plant builder.Connect(nn_system.NN_out_output_port, plant.get_actuation_input_port()) # plant -> NN builder.Connect(plant.get_continuous_state_output_port(), nn_system.NN_in_input_port) # Add meshcat visualizer meshcat = MeshcatVisualizer(scene_graph) builder.AddSystem(meshcat) # builder.Connect(scene_graph.GetOutputPort("lcm_visualization"), builder.Connect(scene_graph.get_pose_bundle_output_port(), meshcat.GetInputPort("lcm_visualization")) # build diagram diagram = builder.Build() meshcat.load() # time.sleep(2.0) RenderSystemWithGraphviz(diagram) # construct simulator simulator = Simulator(diagram) # context = diagram.GetMutableSubsystemContext( # self.station, simulator.get_mutable_context()) simulator.set_publish_every_time_step(False) simulator.set_target_realtime_rate(real_time_rate) simulator.Initialize() sim_duration = 5. simulator.StepTo(sim_duration) print("stepping complete")
def Simulate2dHopper(x0, duration, desired_lateral_velocity=0.0, print_period=0.0): builder = DiagramBuilder() plant = builder.AddSystem(MultibodyPlant(0.0005)) scene_graph = builder.AddSystem(SceneGraph()) plant.RegisterAsSourceForSceneGraph(scene_graph) builder.Connect(plant.get_geometry_poses_output_port(), scene_graph.get_source_pose_port(plant.get_source_id())) builder.Connect(scene_graph.get_query_output_port(), plant.get_geometry_query_input_port()) # Build the plant parser = Parser(plant) parser.AddModelFromFile("raibert_hopper_2d.sdf") plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("ground")) plant.AddForceElement(UniformGravityFieldElement()) plant.Finalize() # Create a logger to log at 30hz state_dim = plant.num_positions() + plant.num_velocities() state_log = builder.AddSystem(SignalLogger(state_dim)) state_log.DeclarePeriodicPublish(0.0333, 0.0) # 30hz logging builder.Connect(plant.get_continuous_state_output_port(), state_log.get_input_port(0)) # The controller controller = builder.AddSystem( Hopper2dController(plant, desired_lateral_velocity=desired_lateral_velocity, print_period=print_period)) builder.Connect(plant.get_continuous_state_output_port(), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), plant.get_actuation_input_port()) # The diagram diagram = builder.Build() simulator = Simulator(diagram) simulator.Initialize() plant_context = diagram.GetMutableSubsystemContext( plant, simulator.get_mutable_context()) plant_context.get_mutable_discrete_state_vector().SetFromVector(x0) simulator.StepTo(duration) return plant, controller, state_log
def animate_cartpole(policy, duration=10.): # Animate the resulting policy. builder = DiagramBuilder() tree = RigidBodyTree("/opt/underactuated/src/cartpole/cartpole.urdf", FloatingBaseType.kFixed) plant = RigidBodyPlant(tree) plant_system = builder.AddSystem(plant) # TODO(russt): add wrap-around logic to barycentric mesh # (so the policy has it, too) class WrapTheta(VectorSystem): def __init__(self): VectorSystem.__init__(self, 4, 4) def _DoCalcVectorOutput(self, context, input, state, output): output[:] = input twoPI = 2.*math.pi output[1] = output[1] - twoPI * math.floor(output[1] / twoPI) wrap = builder.AddSystem(WrapTheta()) builder.Connect(plant_system.get_output_port(0), wrap.get_input_port(0)) vi_policy = builder.AddSystem(policy) builder.Connect(wrap.get_output_port(0), vi_policy.get_input_port(0)) builder.Connect(vi_policy.get_output_port(0), plant_system.get_input_port(0)) logger = builder.AddSystem(SignalLogger(4)) logger._DeclarePeriodicPublish(0.033333, 0.0) builder.Connect(plant_system.get_output_port(0), logger.get_input_port(0)) diagram = builder.Build() simulator = Simulator(diagram) simulator.set_publish_every_time_step(False) state = simulator.get_mutable_context().get_mutable_continuous_state_vector() state.SetFromVector([-1., math.pi-1, 1., -1.]) # Do the sim. simulator.StepTo(duration) # Visualize the result as a video. vis = PlanarRigidBodyVisualizer(tree, xlim=[-12.5, 12.5], ylim=[-1, 2.5]) ani = vis.animate(logger, repeat=True) # plt.show() # Things added to get visualizations in an ipynb plt.close(vis.fig) HTML(ani.to_html5_video())
def RunPendulumSimulation(pendulum_plant, pendulum_controller, x0=[0.9, 0.0], duration=10): ''' Accepts a pendulum_plant (which should be a DampedOscillatingPendulumPlant) and simulates it for 'duration' seconds from initial state `x0`. Returns a logger object which can return simulated timesteps ` logger.sample_times()` (N-by-1) and simulated states `logger.data()` (2-by-N). ''' # Create a simple block diagram containing the plant in feedback # with the controller. builder = DiagramBuilder() plant = builder.AddSystem(pendulum_plant) controller = builder.AddSystem(pendulum_controller) builder.Connect(plant.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), plant.get_input_port(0)) # Create a logger to capture the simulation of our plant # (We tell the logger to expect a 3-variable input, # and hook it up to the pendulum plant's 3-variable output.) logger = builder.AddSystem(SignalLogger(3)) logger._DeclarePeriodicPublish(0.033333, 0.0) builder.Connect(plant.get_output_port(0), logger.get_input_port(0)) diagram = builder.Build() # Create the simulator. simulator = Simulator(diagram) simulator.Initialize() simulator.set_publish_every_time_step(False) # Set the initial conditions for the simulation. state = simulator.get_mutable_context().get_mutable_state()\ .get_mutable_continuous_state().get_mutable_vector() state.SetFromVector(x0) # Simulate for the requested duration. simulator.StepTo(duration) # Return the logger, which stores the output of the # plant across the time steps of the simulation. return logger
def runManipulationExample(args): builder = DiagramBuilder() station = builder.AddSystem(ManipulationStation(time_step=0.005)) station.SetupDefaultStation() station.Finalize() plant = station.get_multibody_plant() scene_graph = station.get_scene_graph() pose_bundle_output_port = station.GetOutputPort("pose_bundle") # Side-on view of the station. Tview = np.array([[1., 0., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]], dtype=np.float64) visualizer = builder.AddSystem(PlanarSceneGraphVisualizer( scene_graph, Tview=Tview, xlim=[-0.5, 1.0], ylim=[-1.2, 1.2], draw_period=0.1)) builder.Connect(pose_bundle_output_port, visualizer.get_input_port(0)) diagram = builder.Build() simulator = Simulator(diagram) simulator.Initialize() simulator.set_target_realtime_rate(1.0) # Fix the control inputs to zero. station_context = diagram.GetMutableSubsystemContext( station, simulator.get_mutable_context()) station.GetInputPort("iiwa_position").FixValue( station_context, station.GetIiwaPosition(station_context)) station.GetInputPort("iiwa_feedforward_torque").FixValue( station_context, np.zeros(7)) station.GetInputPort("wsg_position").FixValue( station_context, np.zeros(1)) station.GetInputPort("wsg_force_limit").FixValue( station_context, [40.0]) simulator.StepTo(args.duration)
diagram = builder.Build() simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(True) # kinsol = rtree.doKinematics(q) # com = rtree.centerOfMass(kinsol) # print com # nominal standing state # state = simulator.get_mutable_context().get_mutable_continuous_state_vector() # state.SetFromVector(q+qd) cassie.set_state_vector(simulator.get_mutable_context(), x) simulator.StepTo(1.0) # simulator.Initialize(); # from bot_lcmgl import lcmgl # import lcm as true_lcm # viz_lcmgl = lcmgl("Visualize-Points", true_lcm.LCM()) # cache = rtree.doKinematics(x[:23], x[23:]) # thigh_l = rtree.transformPoints(cache, GetFourBarHipMountPoint(), # rtree.FindBodyIndex("thigh_left"), 0) # heel_l = rtree.transformPoints(cache, GetFourBarHeelMountPoint(), # rtree.FindBodyIndex("heel_spring_left"), 0) # thigh_r = rtree.transformPoints(cache, -GetFourBarHipMountPoint(), # rtree.FindBodyIndex("thigh_right"), 0) # heel_r = rtree.transformPoints(cache, GetFourBarHeelMountPoint(), # rtree.FindBodyIndex("heel_spring_right"), 0)
def RunSimulation(robobee_plantBS, control_law, x0=np.random.random((15, 1)), duration=30): robobee_controller = RobobeeController(control_law) # Create a simple block diagram containing the plant in feedback # with the controller. builder = DiagramBuilder() # The last pendulum plant we made is now owned by a deleted # system, so easiest path is for us to make a new one. plant = builder.AddSystem( RobobeePlantBS(m=robobee_plantBS.m, Ixx=robobee_plantBS.Ixx, Iyy=robobee_plantBS.Iyy, Izz=robobee_plantBS.Izz, g=robobee_plantBS.g, input_max=robobee_plantBS.input_max)) Rigidbody_selector = builder.AddSystem(RigidBodySelection()) print("1. Connecting plant and controller\n") controller = builder.AddSystem(robobee_controller) builder.Connect(plant.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), plant.get_input_port(0)) # Create a logger to capture the simulation of our plant print("2. Connecting plant to the logger\n") set_time_interval = 0.001 time_interval_multiple = 1000 publish_period = set_time_interval * time_interval_multiple input_log = builder.AddSystem(SignalLogger(4)) # input_log._DeclarePeriodicPublish(0.033333, 0.0) builder.Connect(controller.get_output_port(0), input_log.get_input_port(0)) state_log = builder.AddSystem(SignalLogger(15)) # state_log._DeclarePeriodicPublish(0.033333, 0.0) builder.Connect(plant.get_output_port(0), state_log.get_input_port(0)) # Drake visualization print("3. Connecting plant output to DrakeVisualizer\n") rtree = RigidBodyTree( FindResourceOrThrow("drake/examples/robobee/robobee_arena.urdf"), FloatingBaseType.kQuaternion) #robobee_twobar lcm = DrakeLcm() visualizer = builder.AddSystem( DrakeVisualizer(tree=rtree, lcm=lcm, enable_playback=True)) builder.Connect(plant.get_output_port(0), Rigidbody_selector.get_input_port(0)) builder.Connect(Rigidbody_selector.get_output_port(0), visualizer.get_input_port(0)) print("4. Building diagram\n") diagram = builder.Build() # Set the initial conditions for the simulation. context = diagram.CreateDefaultContext() state = context.get_mutable_continuous_state_vector() state.SetFromVector(x0) # Create the simulator. print("5. Create simulation\n") simulator = Simulator(diagram, context) simulator.Initialize() # simulator.set_publish_every_time_step(False) simulator.set_target_realtime_rate(1) simulator.get_integrator().set_fixed_step_mode(True) simulator.get_integrator().set_maximum_step_size(0.05) # Simulate for the requested duration. simulator.StepTo(duration) return input_log, state_log
def draw(self, context): xy = self.EvalVectorInput(context, 0).CopyToVector() self.lines.set_xdata(xy[:self.num_particles]) self.lines.set_ydata(xy[self.num_particles:]) self.ax.set_title('t = ' + str(context.get_time())) builder = DiagramBuilder() num_particles = 5000 xlim = [-2.75, 2.75] ylim = [-3.25, 3.25] draw_timestep = .25 sys = builder.AddSystem(VanDerPolParticles(num_particles)) visualizer = builder.AddSystem( Particle2DVisualizer(num_particles, xlim, ylim, draw_timestep)) builder.Connect(sys.get_output_port(0), visualizer.get_input_port(0)) AddRandomInputs(.1, builder) # TODO(russt): Plot nominal limit cycle. diagram = builder.Build() simulator = Simulator(diagram) simulator.set_publish_every_time_step(False) simulator.get_mutable_integrator().set_fixed_step_mode(True) simulator.get_mutable_integrator().set_maximum_step_size(0.1) simulator.StepTo(20) plt.show()
def Simulate2dHopper(x0, duration, desired_lateral_velocity=0.0, print_period=0.0): builder = DiagramBuilder() # Load in the hopper from a description file. # It's spawned with a fixed floating base because # the robot description file includes the world as its # root link -- it does this so that I can create a robot # system with planar dynamics manually. (Drake doesn't have # a planar floating base type accessible right now that I # know about -- it only has 6DOF floating base types.) tree = RigidBodyTree() AddModelInstancesFromSdfString( open("raibert_hopper_2d.sdf", 'r').read(), FloatingBaseType.kFixed, None, tree) # A RigidBodyPlant wraps a RigidBodyTree to allow # forward dynamical simulation. It handles e.g. collision # modeling. plant = builder.AddSystem(RigidBodyPlant(tree)) # Alter the ground material used in simulation to make # it dissipate more energy (to make the hopping more critical) # and stickier (to make the hopper less likely to slip). allmaterials = CompliantMaterial() allmaterials.set_youngs_modulus(1E8) # default 1E9 allmaterials.set_dissipation(1.0) # default 0.32 allmaterials.set_friction(1.0) # default 0.9. plant.set_default_compliant_material(allmaterials) # Spawn a controller and hook it up controller = builder.AddSystem( Hopper2dController(tree, desired_lateral_velocity=desired_lateral_velocity, print_period=print_period)) builder.Connect(plant.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), plant.get_input_port(0)) # Create a logger to log at 30hz state_log = builder.AddSystem(SignalLogger(plant.get_num_states())) state_log._DeclarePeriodicPublish(0.0333, 0.0) # 30hz logging builder.Connect(plant.get_output_port(0), state_log.get_input_port(0)) # Create a simulator diagram = builder.Build() simulator = Simulator(diagram) # Don't limit realtime rate for this sim, since we # produce a video to render it after simulating the whole thing. #simulator.set_target_realtime_rate(100.0) simulator.set_publish_every_time_step(False) # Force the simulator to use a fixed-step integrator, # which is much faster for this stiff system. (Due to the # spring-model of collision, the default variable-timestep # integrator will take very short steps. I've chosen the step # size here to be fast while still being stable in most situations.) integrator = simulator.get_mutable_integrator() integrator.set_fixed_step_mode(True) integrator.set_maximum_step_size(0.0005) # Set the initial state state = simulator.get_mutable_context( ).get_mutable_continuous_state_vector() state.SetFromVector(x0) # Simulate! simulator.StepTo(duration) return tree, controller, state_log
#Data Logger logger = LogOutput(plant.get_continuous_state_output_port(), builder) #Run Simulation diagram = builder.Build() simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.) plant_context = diagram.GetMutableSubsystemContext( plant, simulator.get_mutable_context()) print plant_context.get_mutable_discrete_state_vector() plant_context.get_mutable_discrete_state_vector().SetFromVector(x0) simulator.Initialize() simulator.StepTo(duration) #print('sample_times',logger.sample_times()) #nx1 array print('Final State: ', logger.data()[:, -1]) #nxm array x_log = logger.data()[4, :] data = logger.data() theta_log = np.asarray([ math.asin(2 * (data[0, i] * data[2, i] - data[1, i] * data[3, i])) for i in range(data.shape[1]) ]) #theta = math.asin(2*(x[0]*x[2] - x[1]*x[3])) print('Cost: ', np.matmul(theta_log, theta_log.T)) ''' #print('x evolution: ',logger.data()[1,:]) #nxm array #print('y evolution: ',logger.data()[2,:]) #nxm array #print('z evolution: ',logger.data()[3,:]) #nxm array
class DrakeEnv(gym.Env): metadata = {'render.modes': ['human']} def __init__(self): ''' Sets up the System diagram and creates a drake visualizer object to send LCM messages to during the render method. Subclasses must implement the methods below that throw a NotImplementedError ''' # Create the Diagram. self.system = self.plant_system() self.context = self.system.CreateDefaultContext() # Create the simulator. self.simulator = Simulator(self.system, self.context) self.simulator.set_publish_every_time_step(False) def seed(self, seed=None): self.np_random, seed = seeding.np_random(seed) return [seed] def plant_system(self): ''' Returns the fully constructed MDP diagram which is connected to the vector source for simulation. Each subclass should implement this method. ''' raise NotImplementedError def get_input_port_action(self): ''' Returns the system input port that corresponds to the action ''' raise NotImplementedError def get_observation(self): ''' Returns the system output port that corresponds to the observation ''' raise NotImplementedError def get_state(self): ''' Returns the system output port that corresponds to the observation ''' raise NotImplementedError @property def action_space(self): ''' Specifies the limits of tha action space. This must be overridden by subclasses. ''' raise NotImplementedError @property def observation_space(self): ''' Specifies the limits of tha action space. This must be overridden by subclasses. ''' raise NotImplementedError def get_reward(self, state, action): ''' Computes the reward from the state and an action ''' raise NotImplementedError def reset_state(self): ''' Computes the reward from the state and an action ''' raise NotImplementedError def step(self, action): ''' Simulates the system diagram for a short period of time ''' # Only allow valid actions from the action space action = validate_action(action, self.action_space) # Fix input port with action and simulate action_fixed_input_port_value = self.context.FixInputPort( self.get_input_port_action().get_index(), action) self.simulator.StepTo(self.context.get_time() + self.dt) # Get the observation, reward, and terminal conditions state = self.get_state() observation = self.get_observation() reward = self.get_reward(state, action) done = self.is_done() info = {} return observation, reward, done, info def reset(self): ''' Resets the state in the system diagram ''' self.context.set_time(0) self.reset_state() return self.get_observation() def render(self, mode='human', close=False): ''' Notifies the visualizer to draw the current state. Different implementations based on MultiBodyPlant and RigidBodyTree ''' raise NotImplementedError
logger_x = builder.AddSystem(SignalLogger(n)) logger_u = builder.AddSystem(SignalLogger(m)) builder.Connect(controller.get_output_port(0), quad.get_input_port(0)) builder.Connect(quad.get_output_port(0), logger_x.get_input_port(0)) builder.Connect(quad.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), logger_u.get_input_port(0)) diagram = builder.Build() # Create the simulator. simulator = Simulator(diagram) # Set the initial conditions, x(0). state = simulator.get_mutable_context().get_mutable_continuous_state_vector() x0 = np.zeros(n) x0[0:3] = 0.5 x0[5] = np.pi / 2 state.SetFromVector(x0) # Simulate simulator.StepTo(5.0) #%% plot PlotTraj(logger_x.data().T, None, None, logger_x.sample_times()) #%% open meshcat vis = meshcat.Visualizer() vis.open() #%% meshcat animation PlotTrajectoryMeshcat(logger_x.data().T, logger_x.sample_times(), vis)
builder.Connect(quad.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), logger_u.get_input_port(0)) diagram = builder.Build() # Create the simulator. simulator = Simulator(diagram) # if __name__ == '__main__': # Set the initial conditions, x(0). state = simulator.get_mutable_context().get_mutable_continuous_state_vector() state.SetFromVector(traj_specs.x0) input_vector = simulator.get_mutable_context( ).get_mutable_discrete_state_vector() input_vector.SetFromVector(traj_specs.u0) #%% Simulate simulator.StepTo(h * 300) #%% plot PlotTraj(logger_x.data().T, dt=None, xw_list=traj_specs.xw_list, t=logger_x.sample_times()) #%% open meshcat vis = meshcat.Visualizer() vis.open() #%% meshcat animation wpts_list = np.zeros((len(traj_specs.xw_list) + 1, 3)) for i, xw in enumerate(traj_specs.xw_list): wpts_list[i] = xw.x[0:3]
integrator.set_fixed_step_mode(True) integrator.set_maximum_step_size(0.001) #%% # simulate context = simulator.get_mutable_context() x0 = np.array([0., 0., 3., 0.]) # since the ZOH block at t=0 returns its internal state, I have to compute the first feedback "offline" state_c = context.get_mutable_continuous_state_vector() state_c.SetFromVector(x0) state_d = context.get_mutable_discrete_state_vector() u0 = np.empty(pwa.nu) controller._DoCalcVectorOutput(context, x0, None, u0) state_d.SetFromVector(u0) # run sim simulator.StepTo(3.) #%% # visualize viz = PlanarRigidBodyVisualizer(tree, xlim=[-1, 1], ylim=[-2.5, 3.]) viz.fig.set_size_inches(10, 5) ani = viz.animate(state_log, 30, repeat=True) plt.close(viz.fig) HTML(ani.to_html5_video()) # print 'hi Ash'
def SimulateHand(duration=10., num_fingers=3, mu=0.5, manipuland_sdf="models/manipuland_box.sdf", initial_manipuland_pose=np.array([1.5, 0., 0.]), n_grasp_search_iters=100, manipuland_trajectory_callback=None, control_period=0.0333, print_period=1.0): ''' Given a great many passthrough arguments (see docs for HandController and usage example in set_5_mpc.ipynb), constructs a simulation of a num_fingers-fingered hand and simulates it for duration seconds from a specified initial manipuland pose. Returns: (hand, plant, controller, state_log, contact_log) hand: The RigidBodyTree of the complete hand. plant: The RigidBodyPlant that owns the hand RBT controller: The HandController object state_log: A SignalLogger that has logged the output of the state output port of plant. contact_log: A PlanarHandContactLogger object that has logged the output of the contact results output port of the plant. ''' builder = DiagramBuilder() tree = BuildHand(num_fingers, manipuland_sdf) num_finger_links = 3 # from sdf num_hand_q = num_finger_links * num_fingers # Generate the nominal posture for the hand # First link wide open, next links at right angles x_nom = np.zeros(2 * num_finger_links * num_fingers + 6) for i in range(num_fingers): if i < num_fingers / 2: x_nom[(num_finger_links*i):(num_finger_links*(i+1))] = \ np.array([2, 1.57, 1.57]) else: x_nom[(num_finger_links*i):(num_finger_links*(i+1))] = \ -np.array([2, 1.57, 1.57]) # Drop in the initial manipuland location x_nom[num_hand_q:(num_hand_q + 3)] = initial_manipuland_pose # A RigidBodyPlant wraps a RigidBodyTree to allow # forward dynamical simulation. It handles e.g. collision # modeling. plant = builder.AddSystem(RigidBodyPlant(tree)) # Alter the ground material used in simulation to make # it dissipate more energy (to make the object less bouncy) # and stickier (to make it easier to hold) and softer # (again to make it less bouncy) allmaterials = CompliantMaterial() allmaterials.set_youngs_modulus(1E6) # default 1E9 allmaterials.set_dissipation(1.0) # default 0.32 allmaterials.set_friction(0.9) # default 0.9. plant.set_default_compliant_material(allmaterials) # Spawn a controller and hook it up controller = builder.AddSystem( HandController( tree, x_nom=x_nom, num_fingers=num_fingers, mu=mu, n_grasp_search_iters=n_grasp_search_iters, manipuland_trajectory_callback=manipuland_trajectory_callback, control_period=control_period, print_period=print_period)) nq = controller.nq qinit, info = controller.ComputeTargetPosture(x_nom, x_nom[(nq - 3):nq], backoff_distance=0.0) if info != 1: print "Warning: initial condition IK solve returned info ", info xinit = np.zeros(x_nom.shape) xinit[0:(nq - 3)] = qinit[0:-3] xinit[(nq - 3):nq] = x_nom[(nq - 3):nq] builder.Connect(plant.get_output_port(0), controller.get_input_port(0)) for i in range(num_fingers): builder.Connect(controller.get_output_port(i), plant.get_input_port(i)) # Create a state logger to log at 30hz state_log = builder.AddSystem(SignalLogger(plant.get_num_states())) state_log.DeclarePeriodicPublish(0.0333, 0.0) # 30hz logging builder.Connect(plant.get_output_port(0), state_log.get_input_port(0)) # And a contact result logger, same rate contact_log = builder.AddSystem(PlanarHandContactLogger(controller, plant)) contact_log.DeclarePeriodicPublish(0.0333, 0.0) builder.Connect(plant.contact_results_output_port(), contact_log.get_input_port(0)) # Create a simulator diagram = builder.Build() simulator = Simulator(diagram) # Don't limit realtime rate for this sim, since we # produce a video to render it after simulating the whole thing. # simulator.set_target_realtime_rate(100.0) simulator.set_publish_every_time_step(False) # Force the simulator to use a fixed-step integrator, # which is much faster for this stiff system. (Due to the # spring-model of collision, the default variable-timestep # integrator will take very short steps. I've chosen the step # size here to be fast while still being stable in most situations.) integrator = simulator.get_mutable_integrator() integrator.set_fixed_step_mode(True) integrator.set_maximum_step_size(0.005) # Set the initial state state = simulator.get_mutable_context().\ get_mutable_continuous_state_vector() state.SetFromVector(xinit) # Simulate! simulator.StepTo(duration) return tree, plant, controller, state_log, contact_log
def getPredictedMotion(B, v_command, time): #object_positions = object_positions + 0.1 #manipulator_positions = manipulator_positions + 0.1 #object_velocities = object_velocities + 0.1 #manipulator_velocities = manipulator_velocities + 0.1 #object_positions = object_positions[:, range(0,object_positions.shape[1],2)] #manipulator_positions = manipulator_positions[:, range(0,manipulator_positions.shape[1],2)] #object_velocities = object_velocities[:, range(0,object_velocities.shape[1],2)] #manipulator_velocities = manipulator_velocities[:, range(0,manipulator_velocities.shape[1],2)] #times = times[range(0,times.size,2)] #import pdb; pdb.set_trace() step = 0.01 A = 10 * np.eye(3) tree = RigidBodyTree( FindResource( os.path.dirname(os.path.realpath(__file__)) + "/block_pusher2.urdf"), FloatingBaseType.kFixed) # Set up a block diagram with the robot (dynamics), the controller, and a # visualization block. builder = DiagramBuilder() #robot = builder.AddSystem(RigidBodyPlant(tree)) robot = builder.AddSystem( QuasiStaticRigidBodyPlant(tree, step, A, np.linalg.inv(B))) controller = builder.AddSystem(QController(tree, v_command, step)) #builder.Connect(robot.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), robot.get_input_port(0)) Tview = np.array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 0., 1.]], dtype=np.float64) visualizer = builder.AddSystem( PlanarRigidBodyVisualizer(tree, Tview, xlim=[-2.8, 4.8], ylim=[-2.8, 10])) builder.Connect(robot.get_output_port(0), visualizer.get_input_port(0)) logger = builder.AddSystem( SignalLogger(tree.get_num_positions() + tree.get_num_velocities())) builder.Connect(robot.get_output_port(0), logger.get_input_port(0)) diagram = builder.Build() # Set up a simulator to run this diagram simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(True) # Set the initial conditions context = simulator.get_mutable_context() state = context.get_mutable_discrete_state_vector() start1 = 3 * np.pi / 16 start2 = 15 * np.pi / 16 #np.pi/6 - eps, 2*np.pi/3 + eps, -np.pi/6 + eps, -2*np.pi/3 - eps, np.pi/6 - eps, 2*np.pi/3 + eps, -np.pi/6 + eps, -2*np.pi/3 - eps state.SetFromVector( (start1, start2, -start1, -start2, np.pi + start1, start2, np.pi - start1, -start2, 1, 1, 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.)) # (theta1, theta2, theta1dot, theta2dot) # Simulate for 10 seconds simulator.StepTo(time) #import pdb; pdb.set_trace() return (logger.data()[8:11, :], logger.data()[:8, :], logger.data()[19:22, :], logger.data()[11:19, :], logger.sample_times())
import matplotlib.pyplot as plt from pydrake.all import (DiagramBuilder, SignalLogger, Simulator) from simple_continuous_time_system import * # Create a simple block diagram containing our system. builder = DiagramBuilder() system = builder.AddSystem(SimpleContinuousTimeSystem()) logger = builder.AddSystem(SignalLogger(1)) builder.Connect(system.get_output_port(0), logger.get_input_port(0)) diagram = builder.Build() # Create the simulator. simulator = Simulator(diagram) # Set the initial conditions, x(0). state = simulator.get_mutable_context().get_mutable_continuous_state_vector() state.SetFromVector([0.9]) # Simulate for 10 seconds. simulator.StepTo(10) # Plot the results. plt.plot(logger.sample_times(), logger.data().transpose()) plt.xlabel('t') plt.ylabel('x(t)') plt.show()
# Create a simple block diagram containing our system. controller = builder.AddSystem(QuadLqrController()) logger_x = builder.AddSystem(SignalLogger(n)) logger_u = builder.AddSystem(SignalLogger(m)) builder.Connect(controller.get_output_port(0), quad.get_input_port(0)) builder.Connect(quad.get_output_port(0), logger_x.get_input_port(0)) builder.Connect(quad.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), logger_u.get_input_port(0)) diagram = builder.Build() # Create the simulator. simulator = Simulator(diagram) # Set the initial conditions, x(0). state = simulator.get_mutable_context().get_mutable_continuous_state_vector() state.SetFromVector(traj_specs.x0) # Simulate simulator.StepTo(traj_specs.h * traj_specs.N) #%% plot PlotTraj(logger_x.data().T, None, None, logger_x.sample_times()) #%% open meshcat vis = meshcat.Visualizer() vis.open() #%% meshcat animation PlotTrajectoryMeshcat(logger_x.data().T, logger_x.sample_times(), vis)
tree.compile() builder = DiagramBuilder() compass_gait = builder.AddSystem(CompassGait()) parser = argparse.ArgumentParser() parser.add_argument("-T", "--duration", type=float, help="Duration to run sim.", default=10.0) args = parser.parse_args() visualizer = builder.AddSystem( PlanarRigidBodyVisualizer(tree, xlim=[-1., 5.], ylim=[-1., 2.], figsize_multiplier=2)) builder.Connect(compass_gait.get_output_port(1), visualizer.get_input_port(0)) diagram = builder.Build() simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) context = simulator.get_mutable_context() diagram.Publish(context) # draw once to get the window open context.set_accuracy(1e-4) context.SetContinuousState([0., 0., 0.4, -2.]) simulator.StepTo(args.duration)
source = builder.AddSystem(TrajectorySource(q_traj, output_derivative_order=1)) # controller kp = 100 * np.ones(7) kd = 10 * np.ones(7) ki = 0 * np.ones(7) controller = builder.AddSystem(InverseDynamicsController(robot=tree_1, kp=kp, ki=ki, kd=kd, has_reference_acceleration=False)) # plant plant = RigidBodyPlant(tree_2, 0.0005) kuka = builder.AddSystem(plant) # visualizer lcm = DrakeLcm() visualizer = builder.AddSystem(DrakeVisualizer(tree=tree_1, lcm=lcm, enable_playback=True)) visualizer.set_publish_period(.001) # build the diagram builder.Connect(source.get_output_port(0), controller.get_input_port(1)) builder.Connect(controller.get_output_port(0), kuka.get_input_port(0)) builder.Connect(kuka.get_output_port(0), visualizer.get_input_port(0)) builder.Connect(kuka.get_output_port(0), controller.get_input_port(0)) diagram = builder.Build() # run the simulator simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(True) kuka.set_state_vector(simulator.get_mutable_context(), x_init) simulator.StepTo(tspan[-1])