def test_cart_pole(self): """Cart-Pole with simple geometry.""" file_name = FindResourceOrThrow( "drake/examples/multibody/cart_pole/cart_pole.sdf") builder = DiagramBuilder() cart_pole, scene_graph = AddMultibodyPlantSceneGraph(builder) Parser(plant=cart_pole).AddModelFromFile(file_name) cart_pole.AddForceElement(UniformGravityFieldElement()) cart_pole.Finalize() assert cart_pole.geometry_source_is_registered() visualizer = builder.AddSystem( MeshcatVisualizer(scene_graph, zmq_url=None, open_browser=False)) builder.Connect(scene_graph.get_pose_bundle_output_port(), visualizer.get_input_port(0)) diagram = builder.Build() diagram_context = diagram.CreateDefaultContext() cart_pole_context = diagram.GetMutableSubsystemContext( cart_pole, diagram_context) cart_pole_context.FixInputPort( cart_pole.get_actuation_input_port().get_index(), [0]) cart_slider = cart_pole.GetJointByName("CartSlider") pole_pin = cart_pole.GetJointByName("PolePin") cart_slider.set_translation(context=cart_pole_context, translation=0.) pole_pin.set_angle(context=cart_pole_context, angle=2.) simulator = Simulator(diagram, diagram_context) simulator.set_publish_every_time_step(False) simulator.StepTo(.1)
def test_kuka(self): """Kuka IIWA with mesh geometry.""" file_name = FindResourceOrThrow( "drake/manipulation/models/iiwa_description/sdf/" "iiwa14_no_collision.sdf") builder = DiagramBuilder() kuka, scene_graph = AddMultibodyPlantSceneGraph(builder) Parser(plant=kuka).AddModelFromFile(file_name) kuka.AddForceElement(UniformGravityFieldElement()) kuka.Finalize() visualizer = builder.AddSystem( MeshcatVisualizer(scene_graph, zmq_url=None, open_browser=False)) builder.Connect(scene_graph.get_pose_bundle_output_port(), visualizer.get_input_port(0)) diagram = builder.Build() diagram_context = diagram.CreateDefaultContext() kuka_context = diagram.GetMutableSubsystemContext( kuka, diagram_context) kuka_context.FixInputPort( kuka.get_actuation_input_port().get_index(), np.zeros(kuka.get_actuation_input_port().size())) simulator = Simulator(diagram, diagram_context) simulator.set_publish_every_time_step(False) simulator.StepTo(.1)
def main(): parser = argparse.ArgumentParser(description=__doc__) parser.add_argument( "--target_realtime_rate", type=float, default=1.0, help="Desired rate relative to real time. See documentation for " "Simulator::set_target_realtime_rate() for details.") parser.add_argument("--simulation_time", type=float, default=10.0, help="Desired duration of the simulation in seconds.") parser.add_argument( "--time_step", type=float, default=0., help="If greater than zero, the plant is modeled as a system with " "discrete updates and period equal to this time_step. " "If 0, the plant is modeled as a continuous system.") args = parser.parse_args() file_name = FindResourceOrThrow( "drake/examples/multibody/cart_pole/cart_pole.sdf") builder = DiagramBuilder() scene_graph = builder.AddSystem(SceneGraph()) cart_pole = builder.AddSystem(MultibodyPlant(time_step=args.time_step)) AddModelFromSdfFile(file_name=file_name, plant=cart_pole, scene_graph=scene_graph) cart_pole.AddForceElement(UniformGravityFieldElement([0, 0, -9.81])) cart_pole.Finalize(scene_graph) assert cart_pole.geometry_source_is_registered() builder.Connect( cart_pole.get_geometry_poses_output_port(), scene_graph.get_source_pose_port(cart_pole.get_source_id())) lcm = DrakeLcm() ConnectVisualization(scene_graph=scene_graph, builder=builder, lcm=lcm) diagram = builder.Build() DispatchLoadMessage(scene_graph=scene_graph, lcm=lcm) diagram_context = diagram.CreateDefaultContext() cart_pole_context = diagram.GetMutableSubsystemContext( cart_pole, diagram_context) cart_pole_context.FixInputPort( cart_pole.get_actuation_input_port().get_index(), [0]) cart_slider = cart_pole.GetJointByName("CartSlider") pole_pin = cart_pole.GetJointByName("PolePin") cart_slider.set_translation(context=cart_pole_context, translation=0.) pole_pin.set_angle(context=cart_pole_context, angle=2.) simulator = Simulator(diagram, diagram_context) simulator.set_publish_every_time_step(False) simulator.set_target_realtime_rate(args.target_realtime_rate) simulator.Initialize() simulator.StepTo(args.simulation_time)
def cartPoleTest(self): file_name = FindResourceOrThrow( "drake/examples/multibody/cart_pole/cart_pole.sdf") builder = DiagramBuilder() scene_graph = builder.AddSystem(SceneGraph()) cart_pole = builder.AddSystem(MultibodyPlant()) AddModelFromSdfFile(file_name=file_name, plant=cart_pole, scene_graph=scene_graph) cart_pole.AddForceElement(UniformGravityFieldElement([0, 0, -9.81])) cart_pole.Finalize(scene_graph) assert cart_pole.geometry_source_is_registered() builder.Connect( cart_pole.get_geometry_poses_output_port(), scene_graph.get_source_pose_port(cart_pole.get_source_id())) visualizer = builder.AddSystem( MeshcatVisualizer(scene_graph, zmq_url=None)) builder.Connect(scene_graph.get_pose_bundle_output_port(), visualizer.get_input_port(0)) diagram = builder.Build() visualizer.load() diagram_context = diagram.CreateDefaultContext() cart_pole_context = diagram.GetMutableSubsystemContext( cart_pole, diagram_context) cart_pole_context.FixInputPort( cart_pole.get_actuation_input_port().get_index(), [0]) cart_slider = cart_pole.GetJointByName("CartSlider") pole_pin = cart_pole.GetJointByName("PolePin") cart_slider.set_translation(context=cart_pole_context, translation=0.) pole_pin.set_angle(context=cart_pole_context, angle=2.) simulator = Simulator(diagram, diagram_context) simulator.set_publish_every_time_step(False) simulator.set_target_realtime_rate(args.target_realtime_rate) simulator.Initialize() simulator.StepTo(args.duration)
def kukaTest(args): file_name = FindResourceOrThrow( "drake/manipulation/models/iiwa_description/sdf/" "iiwa14_no_collision.sdf") builder = DiagramBuilder() scene_graph = builder.AddSystem(SceneGraph()) kuka = builder.AddSystem(MultibodyPlant()) AddModelFromSdfFile(file_name=file_name, plant=kuka, scene_graph=scene_graph) kuka.AddForceElement(UniformGravityFieldElement([0, 0, -9.81])) kuka.Finalize(scene_graph) assert kuka.geometry_source_is_registered() builder.Connect(kuka.get_geometry_poses_output_port(), scene_graph.get_source_pose_port(kuka.get_source_id())) visualizer = builder.AddSystem( MeshcatVisualizer(scene_graph, zmq_url=None)) builder.Connect(scene_graph.get_pose_bundle_output_port(), visualizer.get_input_port(0)) diagram = builder.Build() visualizer.load() diagram_context = diagram.CreateDefaultContext() kuka_context = diagram.GetMutableSubsystemContext( kuka, diagram_context) kuka_context.FixInputPort( kuka.get_actuation_input_port().get_index(), np.zeros(kuka.get_actuation_input_port().size())) simulator = Simulator(diagram, diagram_context) simulator.set_publish_every_time_step(False) simulator.set_target_realtime_rate(args.target_realtime_rate) simulator.Initialize() simulator.StepTo(args.duration)
parser = argparse.ArgumentParser() parser.add_argument("--test", action='store_true', help="Causes the script to run without blocking for " "user input.", default=False) args = parser.parse_args() file_name = FindResourceOrThrow( "drake/examples/multibody/cart_pole/cart_pole.sdf") builder = DiagramBuilder() scene_graph = builder.AddSystem(SceneGraph()) cart_pole = builder.AddSystem(MultibodyPlant()) cart_pole.RegisterAsSourceForSceneGraph(scene_graph) AddModelFromSdfFile(file_name=file_name, plant=cart_pole) cart_pole.AddForceElement(UniformGravityFieldElement([0, 0, -9.81])) cart_pole.Finalize() assert cart_pole.geometry_source_is_registered() builder.Connect(scene_graph.get_query_output_port(), cart_pole.get_geometry_query_input_port()) builder.Connect(cart_pole.get_geometry_poses_output_port(), scene_graph.get_source_pose_port(cart_pole.get_source_id())) builder.ExportInput(cart_pole.get_actuation_input_port()) ConnectDrakeVisualizer(builder=builder, scene_graph=scene_graph) diagram = builder.Build() diagram.set_name("graphviz_example") plot_system_graphviz(diagram, max_depth=2)
parser = argparse.ArgumentParser() parser.add_argument("--test", action='store_true', help="Causes the script to run without blocking for " "user input.", default=False) args = parser.parse_args() file_name = FindResourceOrThrow( "drake/examples/multibody/cart_pole/cart_pole.sdf") builder = DiagramBuilder() scene_graph = builder.AddSystem(SceneGraph()) cart_pole = builder.AddSystem(MultibodyPlant()) cart_pole.RegisterAsSourceForSceneGraph(scene_graph) Parser(plant=cart_pole).AddModelFromFile(file_name) cart_pole.AddForceElement(UniformGravityFieldElement()) cart_pole.Finalize() assert cart_pole.geometry_source_is_registered() builder.Connect(scene_graph.get_query_output_port(), cart_pole.get_geometry_query_input_port()) builder.Connect(cart_pole.get_geometry_poses_output_port(), scene_graph.get_source_pose_port(cart_pole.get_source_id())) builder.ExportInput(cart_pole.get_actuation_input_port()) ConnectDrakeVisualizer(builder=builder, scene_graph=scene_graph) diagram = builder.Build() diagram.set_name("graphviz_example") plot_system_graphviz(diagram, max_depth=2)
def test_multibody_gravity_vector(self): plant = MultibodyPlant() plant.AddForceElement(UniformGravityFieldElement([0.0, -9.81, 0.0])) plant.Finalize()
def test_multibody_gravity_default(self): plant = MultibodyPlant() plant.AddForceElement(UniformGravityFieldElement()) plant.Finalize()
def LittleDogSimulationDiagram2(lcm, rb_tree, dt, drake_visualizer): builder = DiagramBuilder() num_pos = rb_tree.get_num_positions() num_actuators = rb_tree.get_num_actuators() zero_config = np.zeros( (rb_tree.get_num_actuators() * 2, 1)) # just for test # zero_config = np.concatenate((np.array([0, 1, 1, 1, 1.7, 0.5, 0, 0, 0]),np.zeros(9)), axis=0) # zero_config = np.concatenate((rb_tree.getZeroConfiguration(),np.zeros(9)), axis=0) zero_config = np.concatenate( (np.array([1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]), np.zeros(12)), axis=0) # zero_config[0] = 1.7 # zero_config[1] = 1.7 # zero_config[2] = 1.7 # zero_config[3] = 1.7 # 1.SceneGraph system scene_graph = builder.AddSystem(SceneGraph()) scene_graph.RegisterSource('scene_graph_n') plant = builder.AddSystem(MultibodyPlant()) plant_parser = Parser(plant, scene_graph) plant_parser.AddModelFromFile(file_name=model_path, model_name="littledog") plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("body")) # Add gravity to the model. plant.AddForceElement(UniformGravityFieldElement([0, 0, -9.81])) # Model is completed plant.Finalize() builder.Connect(scene_graph.get_query_output_port(), plant.get_geometry_query_input_port()) builder.Connect(plant.get_geometry_poses_output_port(), scene_graph.get_source_pose_port(plant.get_source_id())) ConnectDrakeVisualizer(builder=builder, scene_graph=scene_graph) # Robot State Encoder robot_state_encoder = builder.AddSystem( RobotStateEncoder(rb_tree)) # force_sensor_info robot_state_encoder.set_name('robot_state_encoder') builder.Connect(plant.get_continuous_state_output_port(), robot_state_encoder.joint_state_results_input_port()) # Robot command to Plant Converter robot_command_to_rigidbodyplant_converter = builder.AddSystem( RobotCommandToRigidBodyPlantConverter( rb_tree.actuators, motor_gain=None)) # input argu: rigidbody actuators robot_command_to_rigidbodyplant_converter.set_name( 'robot_command_to_rigidbodyplant_converter') builder.Connect( robot_command_to_rigidbodyplant_converter.desired_effort_output_port(), plant.get_actuation_input_port()) # PID controller kp, ki, kd = joints_PID_params(rb_tree) # PIDcontroller = builder.AddSystem(RobotPDAndFeedForwardController(rb_tree, kp, ki, kd)) # PIDcontroller.set_name('PID_controller') rb = RigidBodyTree() robot_frame = RigidBodyFrame("robot_frame", rb_tree.world(), [0, 0, 0], [0, 0, 0]) # insert a robot from urdf files pmap = PackageMap() pmap.PopulateFromFolder(os.path.dirname(model_path)) AddModelInstanceFromUrdfStringSearchingInRosPackages( open(model_path, 'r').read(), pmap, os.path.dirname(model_path), FloatingBaseType.kFixed, # FloatingBaseType.kRollPitchYaw, robot_frame, rb) PIDcontroller = builder.AddSystem( RbtInverseDynamicsController(rb, kp, ki, kd, False)) PIDcontroller.set_name('PID_controller') builder.Connect(robot_state_encoder.joint_state_outport_port(), PIDcontroller.get_input_port(0)) builder.Connect( PIDcontroller.get_output_port(0), robot_command_to_rigidbodyplant_converter.robot_command_input_port()) # Ref trajectory traj_src = builder.AddSystem(ConstantVectorSource(zero_config)) builder.Connect(traj_src.get_output_port(0), PIDcontroller.get_input_port(1)) # Signal logger logger = builder.AddSystem(SignalLogger(num_pos * 2)) builder.Connect(plant.get_continuous_state_output_port(), logger.get_input_port(0)) return builder.Build(), logger, plant
builder = DiagramBuilder() # 1.SceneGraph system scene_graph = builder.AddSystem(SceneGraph()) scene_graph.RegisterSource('scene_graph_n') # 2.Kuka robot system robot_plant = builder.AddSystem(MultibodyPlant()) AddModelFromSdfFile(file_name=FindResourceOrThrow(kSdfPath), plant = robot_plant, scene_graph= scene_graph ) robot_plant.WeldFrames(robot_plant.world_frame(), robot_plant.GetFrameByName("iiwa_link_0")) # Add gravity to the model. robot_plant.AddForceElement(UniformGravityFieldElement([0, 0, -9.81])) # Model is completed robot_plant.Finalize() # Sanity check on the availability of the optional source id before using it. assert robot_plant.geometry_source_is_registered() assert robot_plant.num_positions() == 7 print('get_source_id : ', robot_plant.get_source_id()) # Boilerplate used to connect the plant to a SceneGraph for visualization. lcm = DrakeLcm builder.Connect(scene_graph.get_query_output_port(), robot_plant.get_geometry_query_input_port()) builder.Connect(robot_plant.get_geometry_poses_output_port(), scene_graph.get_source_pose_port(robot_plant.get_source_id()))