def __init__(self, file_name , Is_fixed = True ): rb_tree = RigidBodyTree() world_frame = RigidBodyFrame("world_frame", rb_tree.world(), [0, 0, 0], [0, 0, 0]) AddFlatTerrainToWorld(rb_tree, 1000, 10) robot_frame = RigidBodyFrame("robot_frame", rb_tree.world(), [0, 0, 0.2], [0, 0, 0]) if Is_fixed is True: self.fixed_type = FloatingBaseType.kFixed else: self.fixed_type = FloatingBaseType.kRollPitchYaw # insert a robot from urdf files pmap = PackageMap() pmap.PopulateFromFolder(os.path.dirname(file_name)) AddModelInstanceFromUrdfStringSearchingInRosPackages( open(file_name, 'r').read(), pmap, os.path.dirname(file_name), self.fixed_type, # FloatingBaseType.kRollPitchYaw, robot_frame, rb_tree) self.rb_tree = rb_tree self.joint_limit_max = self.rb_tree.joint_limit_max self.joint_limit_min = self.rb_tree.joint_limit_min print(self.joint_limit_max) print(self.joint_limit_min)
def test_rgbd_camera(self): sdf_path = FindResourceOrThrow( "drake/systems/sensors/test/models/nothing.sdf") tree = RigidBodyTree() with open(sdf_path) as f: sdf_string = f.read() AddModelInstancesFromSdfString(sdf_string, FloatingBaseType.kFixed, None, tree) frame = RigidBodyFrame("rgbd camera frame", tree.FindBody("link")) tree.addFrame(frame) # Use HDTV size. width = 1280 height = 720 camera = mut.RgbdCamera(name="camera", tree=tree, frame=frame, z_near=0.5, z_far=5.0, fov_y=np.pi / 4, show_window=False, width=width, height=height) def check_info(camera_info): self.assertIsInstance(camera_info, mut.CameraInfo) self.assertEqual(camera_info.width(), width) self.assertEqual(camera_info.height(), height) check_info(camera.color_camera_info()) check_info(camera.depth_camera_info()) self.assertIsInstance(camera.color_camera_optical_pose(), Isometry3) self.assertIsInstance(camera.depth_camera_optical_pose(), Isometry3) self.assertTrue(camera.tree() is tree) # N.B. `RgbdCamera` copies the input frame. self.assertEqual(camera.frame().get_name(), frame.get_name()) self._check_ports(camera) # Test discrete camera. period = mut.RgbdCameraDiscrete.kDefaultPeriod discrete = mut.RgbdCameraDiscrete(camera=camera, period=period, render_label_image=True) self.assertTrue(discrete.camera() is camera) self.assertTrue(discrete.mutable_camera() is camera) self.assertEqual(discrete.period(), period) self._check_ports(discrete) # That we can access the state as images. context = discrete.CreateDefaultContext() values = context.get_abstract_state() self.assertIsInstance(values.get_value(0), Value[mut.ImageRgba8U]) self.assertIsInstance(values.get_value(1), Value[mut.ImageDepth32F]) self.assertIsInstance(values.get_value(2), Value[mut.ImageLabel16I])
def test_rgbd_camera(self): sdf_path = FindResourceOrThrow( "drake/systems/sensors/test/models/nothing.sdf") tree = RigidBodyTree() with open(sdf_path) as f: sdf_string = f.read() AddModelInstancesFromSdfString( sdf_string, FloatingBaseType.kFixed, None, tree) frame = RigidBodyFrame("rgbd camera frame", tree.FindBody("link")) tree.addFrame(frame) # Use HDTV size. width = 1280 height = 720 camera = mut.RgbdCamera( name="camera", tree=tree, frame=frame, z_near=0.5, z_far=5.0, fov_y=np.pi / 4, show_window=False, width=width, height=height) def check_info(camera_info): self.assertIsInstance(camera_info, mut.CameraInfo) self.assertEqual(camera_info.width(), width) self.assertEqual(camera_info.height(), height) check_info(camera.color_camera_info()) check_info(camera.depth_camera_info()) self.assertIsInstance(camera.color_camera_optical_pose(), Isometry3) self.assertIsInstance(camera.depth_camera_optical_pose(), Isometry3) self.assertTrue(camera.tree() is tree) # N.B. `RgbdCamera` copies the input frame. self.assertEqual(camera.frame().get_name(), frame.get_name()) self._check_ports(camera) # Test discrete camera. period = mut.RgbdCameraDiscrete.kDefaultPeriod discrete = mut.RgbdCameraDiscrete( camera=camera, period=period, render_label_image=True) self.assertTrue(discrete.camera() is camera) self.assertTrue(discrete.mutable_camera() is camera) self.assertEqual(discrete.period(), period) self._check_ports(discrete) # That we can access the state as images. context = discrete.CreateDefaultContext() values = context.get_abstract_state() self.assertIsInstance(values.get_value(0), Value[mut.ImageRgba8U]) self.assertIsInstance(values.get_value(1), Value[mut.ImageDepth32F]) self.assertIsInstance(values.get_value(2), Value[mut.ImageLabel16I])
def SetupLittleDog(): # Build up your Robot World rb_tree = RigidBodyTree() world_frame = RigidBodyFrame("world_frame", rb_tree.world(), [0, 0, 0], [0, 0, 0]) AddFlatTerrainToWorld(rb_tree, 1000, 10) robot_frame = RigidBodyFrame("robot_frame", rb_tree.world(), [0, 0, 0.2], [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_tree) return rb_tree
def add_fixed_model(tree, filename, xyz=np.zeros(3), rpy=np.zeros(3)): with open(filename) as f: urdf_string = f.read() base_dir = os.path.dirname(filename) package_map = PackageMap() floating_base_type = FloatingBaseType.kFixed weld_frame = RigidBodyFrame("weld_frame", tree.FindBody("world"), xyz, rpy) AddModelInstanceFromUrdfStringSearchingInRosPackages( urdf_string, package_map, base_dir, floating_base_type, weld_frame, tree)
def SetupKinova(): # Build up your Robot World rb_tree = RigidBodyTree() world_frame = RigidBodyFrame("world_frame", rb_tree.world(), [0, 0, 0], [0, 0, 0]) AddFlatTerrainToWorld(rb_tree, 1000, 10) 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_tree) print("Num of Joints : {}, \n Num of Actuators: {}".format( rb_tree.get_num_positions(), rb_tree.get_num_actuators())) return rb_tree
def test_frame_api(self): tree = RigidBodyTree(FindResourceOrThrow( "drake/examples/pendulum/Pendulum.urdf")) # xyz + rpy frame = RigidBodyFrame( name="frame_1", body=tree.world(), xyz=[0, 0, 0], rpy=[0, 0, 0]) self.assertEqual(frame.get_name(), "frame_1") tree.addFrame(frame) self.assertTrue(frame.get_frame_index() < 0, frame.get_frame_index()) self.assertTrue(frame.get_rigid_body() is tree.world()) self.assertIsInstance(frame.get_transform_to_body(), Isometry3) self.assertTrue(tree.findFrame(frame_name="frame_1") is frame)
robot) return robot urdf_file = os.path.join( pydrake.getDrakePath(), "examples/pr2/models/pr2_description/urdf/pr2_simplified.urdf") # Load our model from URDF robot = load_robot_from_urdf(urdf_file) # Add a convenient frame, positioned 0.1m away from the r_gripper_palm_link # along that link's x axis robot.addFrame( RigidBodyFrame("r_hand_frame", robot.FindBody("r_gripper_palm_link"), np.array([0.1, 0, 0]), np.array([0., 0, 0]))) # Make sure attribute access works on bodies assert robot.world().get_name() == "world" hand_frame_id = robot.findFrame("r_hand_frame").get_frame_index() base_body_id = robot.FindBody('base_footprint').get_body_index() constraints = [ # These three constraints ensure that the base of the robot is # at z = 0 and has no pitch or roll. Instead of directly # constraining orientation, we just require that the points at # [0, 0, 0], [1, 0, 0], and [0, 1, 0] in the robot's base's # frame must all be at z = 0 in world frame. # We don't care about the x or y position of the robot's base, # so we use NaN values to tell the IK solver not to apply a
def LittleDogSimulationDiagram(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([0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5 ]), 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 # RigidBodyPlant plant = builder.AddSystem(RigidBodyPlant(rb_tree, dt)) plant.set_name('plant') # Visualizer visualizer_publisher = builder.AddSystem(drake_visualizer) visualizer_publisher.set_name('visualizer_publisher') visualizer_publisher.set_publish_period(0.02) builder.Connect(plant.state_output_port(), visualizer_publisher.get_input_port(0)) # 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.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_input_port(0)) # 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)) # Robot State handle robot_state_handle = builder.AddSystem( RobotStateHandle(rb_tree)) # force_sensor_info robot_state_handle.set_name('robot_state_handle') builder.Connect(plant.state_output_port(), robot_state_handle.joint_state_results_input_port()) logger_N = 4 logger = [] for i in range(logger_N): logger.append([]) # Signal logger signalLogRate = 100 logger[0] = builder.AddSystem(SignalLogger(num_pos * 2)) logger[0]._DeclarePeriodicPublish(1. / signalLogRate, 0.0) builder.Connect(plant.get_output_port(0), logger[0].get_input_port(0)) # cotroller command logger[1] = builder.AddSystem(SignalLogger(num_actuators)) logger[1]._DeclarePeriodicPublish(1. / signalLogRate, 0.0) builder.Connect(PIDcontroller.get_output_port(0), logger[1].get_input_port(0)) # torque # other logger[2] = builder.AddSystem(SignalLogger(3)) builder.Connect(robot_state_handle.com_outport_port(), logger[2].get_input_port(0)) logger[2]._DeclarePeriodicPublish(1. / signalLogRate, 0.0) logger[3] = builder.AddSystem(SignalLogger(num_actuators)) builder.Connect(plant.torque_output_port(), logger[3].get_input_port(0)) logger[3]._DeclarePeriodicPublish(1. / signalLogRate, 0.0) return builder.Build(), logger, plant
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
) from pydrake.systems.sensors import ( CameraInfo, RgbdCamera, ) # Create tree describing scene. urdf_path = FindResourceOrThrow( "drake/multibody/models/box.urdf") tree = RigidBodyTree() AddModelInstanceFromUrdfFile( urdf_path, FloatingBaseType.kFixed, None, tree) # - Add frame for camera fixture. frame = RigidBodyFrame( name="rgbd camera frame", body=tree.world(), xyz=[-2, 0, 2], # Ensure that the box is within range. rpy=[0, np.pi / 4, 0]) tree.addFrame(frame) # Create camera. camera = RgbdCamera( name="camera", tree=tree, frame=frame, z_near=0.5, z_far=5.0, fov_y=np.pi / 4, show_window=True) # - Describe state. x = np.zeros(tree.get_num_positions() + tree.get_num_velocities()) # Allocate context and render. context = camera.CreateDefaultContext()
# 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_input_port(0)) # PID controller kp, ki, kd = joints_PID_params(rb_tree) rb = rigid_body_tree = 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(RobotPDAndFeedForwardController(rb_tree, kp, ki, kd)) controller = RbtInverseDynamicsController(rb, kp, ki, kd, False) PIDcontroller = builder.AddSystem(controller) PIDcontroller.set_name('PID_controller')