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 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 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 build_block_diagram(actuators_off=False, desired_lateral_velocity=0.0, desired_height=3.0, print_period=0.0): builder = DiagramBuilder() # Build the plant 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 robot parser = Parser(plant) parser.AddModelFromFile("raibert_hopper_2d.sdf") plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("ground")) plant.Finalize() plant.set_name('plant') # 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_state_output_port(), state_log.get_input_port(0)) state_log.set_name('state_log') # The controller controller = builder.AddSystem( Hopper2dController(plant, desired_lateral_velocity=desired_lateral_velocity, desired_height=desired_height, actuators_off=actuators_off, print_period=print_period)) builder.Connect(plant.get_state_output_port(), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), plant.get_actuation_input_port()) controller.set_name('controller') # Create visualizer visualizer = builder.AddSystem( PlanarSceneGraphVisualizer(scene_graph, xlim=[-1, 10], ylim=[-.2, 4.5], show=False)) builder.Connect(scene_graph.get_pose_bundle_output_port(), visualizer.get_input_port(0)) visualizer.set_name('visualizer') diagram = builder.Build() return diagram
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 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 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.AdvanceTo(duration) # Return the logger, which stores the output of the # plant across the time steps of the simulation. return logger
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()
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
control_input_reference = discrete_state.get_mutable_vector( ).get_mutable_value() x = self.EvalVectorInput(context, 0).get_value() u = control_input_reference.copy() new_u = self.ComputeControlInput(x, u, context.get_time()) control_input_reference[:] = new_u def _DoCalcVectorOutput(self, context, y_basic_vector): control_output = context.get_discrete_state_vector().get_value() y = y_basic_vector.get_mutable_value() y[:] = control_output # Create a simple block diagram containing our system. controller = builder.AddSystem(QuadIlqrMpcController()) 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) # if __name__ == '__main__': # Set the initial conditions, x(0). state = simulator.get_mutable_context().get_mutable_continuous_state_vector() state.SetFromVector(traj_specs.x0)
def log_output(output_port, rate): logger = builder.AddSystem(SignalLogger(output_port.size())) logger._DeclarePeriodicPublish(1. / rate, 0.0) builder.Connect(output_port, logger.get_input_port(0)) return logger
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 log_output(output_port, rate): logger = builder.AddSystem(SignalLogger(output_port.size())) logger.set_publish_period(1. / rate) builder.Connect(output_port, logger.get_input_port(0)) return logger
def BuildAndSimulateTrajectory( q_traj, g_traj, get_gripper_controller, T_world_objectInitial, T_world_targetBin, zmq_url, time_step, include_target_bin=True, include_hoop=False, manipuland="foam" ): """Simulate trajectory for manipulation station. @param q_traj: Trajectory class used to initialize TrajectorySource for joints. @param g_traj: Trajectory class used to initialize TrajectorySource for gripper. """ builder = DiagramBuilder() station = builder.AddSystem(ManipulationStation(time_step=time_step)) #1e-3 or 1e-4 probably station.SetupClutterClearingStation() if manipuland is "foam": station.AddManipulandFromFile( "drake/examples/manipulation_station/models/061_foam_brick.sdf", T_world_objectInitial) elif manipuland is "ball": station.AddManipulandFromFile( "drake/examples/manipulation_station/models/sphere.sdf", T_world_objectInitial) elif manipuland is "bball": station.AddManipulandFromFile( "drake/../../../../../../manipulation/sdfs/bball.sdf", # this is some path hackery T_world_objectInitial) elif manipuland is "rod": station.AddManipulandFromFile( "drake/examples/manipulation_station/models/rod.sdf", T_world_objectInitial) station_plant = station.get_multibody_plant() parser = Parser(station_plant) if include_target_bin: parser.AddModelFromFile("sdfs/extra_bin.sdf") station_plant.WeldFrames(station_plant.world_frame(), station_plant.GetFrameByName("extra_bin_base"), T_world_targetBin) if include_hoop: parser.AddModelFromFile("sdfs/hoop.sdf") station_plant.WeldFrames(station_plant.world_frame(), station_plant.GetFrameByName("base_link_hoop"), T_world_targetBin) station.Finalize() # iiwa joint trajectory - predetermined trajectory q_traj_system = builder.AddSystem(TrajectorySource(q_traj)) builder.Connect(q_traj_system.get_output_port(), station.GetInputPort("iiwa_position")) # gripper - closed loop controller gctlr = builder.AddSystem(get_gripper_controller(station_plant)) gctlr.set_name("GripperControllerUsingIiwaState") builder.Connect(station.GetOutputPort("iiwa_position_measured"), gctlr.GetInputPort("iiwa_position")) builder.Connect(station.GetOutputPort("iiwa_velocity_estimated"), gctlr.GetInputPort("iiwa_velocity")) builder.Connect(gctlr.get_output_port(), station.GetInputPort("wsg_position")) loggers = dict( state=builder.AddSystem(SignalLogger(31)), v_est=builder.AddSystem(SignalLogger(7)) ) builder.Connect(station.GetOutputPort("plant_continuous_state"), loggers["state"].get_input_port()) builder.Connect(station.GetOutputPort("iiwa_velocity_estimated"), loggers["v_est"].get_input_port()) meshcat = None if zmq_url is not None: meshcat = ConnectMeshcatVisualizer(builder, station.get_scene_graph(), output_port=station.GetOutputPort("pose_bundle"), delete_prefix_on_load=True, frames_to_draw={"gripper":{"body"}}, zmq_url=zmq_url) diagram = builder.Build() simulator = Simulator(diagram) simulator.set_target_realtime_rate(1.0) return simulator, station_plant, meshcat, loggers
robobee_controller = RobobeeController(test_LQRcontroller) # 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(robobeeplant) 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 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(13)) state_log._DeclarePeriodicPublish(0.033333, 0.0) builder.Connect(plant.get_output_port(0), state_log.get_input_port(0)) # Drake visualization rtree = RigidBodyTree( FindResourceOrThrow("drake/examples/robobee/robobee.urdf"), FloatingBaseType.kQuaternion) lcm = DrakeLcm() visualizer = builder.AddSystem( DrakeVisualizer(tree=rtree, lcm=lcm, enable_playback=True)) builder.Connect(plant.get_output_port(0), visualizer.get_input_port(0))
torque_system = builder.AddSystem( ConstantVectorSource( np.ones((rbt.get_num_actuators(), 1)) * torque)) builder.Connect(torque_system.get_output_port(0), rbplant_sys.get_input_port(0)) print('Simulating with constant torque = ' + str(torque) + ' Newton-meters') # Visualize visualizer = builder.AddSystem(pbrv) builder.Connect(rbplant_sys.get_output_port(0), visualizer.get_input_port(0)) # And also log signalLogRate = 60 signalLogger = builder.AddSystem(SignalLogger(nx)) signalLogger.DeclarePeriodicPublish(1. / signalLogRate, 0.0) builder.Connect(rbplant_sys.get_output_port(0), signalLogger.get_input_port(0)) diagram = builder.Build() simulator = Simulator(diagram) simulator.Initialize() simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(False) # TODO(russt): Clean up state vector access below. state = simulator.get_mutable_context().get_mutable_state()\ .get_mutable_continuous_state().get_mutable_vector() if set_initial_state:
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())
# drake controller (System) controller = Controller(pwa, N, Q, R, Q, X_N) #%% # blocks of the diagram builder = DiagramBuilder() robot = builder.AddSystem(plant) controller = builder.AddSystem(controller) zoh = builder.AddSystem(ZeroOrderHold(.1, 1)) #%% # logger logger_freq = 30. logger = SignalLogger(plant.get_num_states()) state_log = builder.AddSystem(logger) state_log._DeclarePeriodicPublish(1. / logger_freq, 0.0) #%% # connect and build the diagram builder.Connect(robot.get_output_port(0), controller.get_input_port(0)) builder.Connect(controller.get_output_port(0), zoh.get_input_port(0)) builder.Connect(zoh.get_output_port(0), robot.get_input_port(0)) builder.Connect(plant.get_output_port(0), state_log.get_input_port(0)) diagram = builder.Build() #%% # set up sim
def simulate_and_log_policy_system(policy_system, expmt, ic=None): global tree global logger expmt_settings = { "pendulum": { 'constructor_or_path': PendulumPlant, 'state_dim': 2, 'twoPI_boundary_condition_state_idxs': (0,), 'initial_state': [0.1, 0.0], }, "acrobot": { 'constructor_or_path': "/opt/underactuated/src/acrobot/acrobot.urdf", 'state_dim': 4, 'twoPI_boundary_condition_state_idxs': (0, 1), 'initial_state': [0.5, 0.5, 0.0, 0.0], }, "cartpole": { 'constructor_or_path': "/opt/underactuated/src/cartpole/cartpole.urdf", 'state_dim': 4, 'twoPI_boundary_condition_state_idxs': (1,), 'initial_state': [0.5, 0.5, 0.0, 0.0], }, } assert expmt in expmt_settings.keys() # Animate the resulting policy. settings = expmt_settings[expmt] builder = DiagramBuilder() constructor_or_path = settings['constructor_or_path'] if not isinstance(constructor_or_path, str): plant = constructor_or_path() else: tree = RigidBodyTree(constructor_or_path, 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, settings['state_dim'], settings['state_dim']) def _DoCalcVectorOutput(self, context, input, state, output): output[:] = input twoPI = 2.*math.pi for idx in settings['twoPI_boundary_condition_state_idxs']: # output[idx] += math.pi output[idx] = output[idx]# - twoPI * math.floor(output[idx] / twoPI) # output[idx] -= math.pi wrap = builder.AddSystem(WrapTheta()) builder.Connect(plant_system.get_output_port(0), wrap.get_input_port(0)) vi_policy = builder.AddSystem(policy_system) 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)) x_logger = builder.AddSystem(SignalLogger(settings['state_dim'])) x_logger._DeclarePeriodicPublish(0.033333, 0.0) builder.Connect(plant_system.get_output_port(0), x_logger.get_input_port(0)) u_logger = builder.AddSystem(SignalLogger(1)) u_logger._DeclarePeriodicPublish(0.033333, 0.0) builder.Connect(vi_policy.get_output_port(0), u_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() if ic is None: ic = settings['initial_state'] state.SetFromVector(ic) return simulator, tree, x_logger, u_logger
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