# create world world = BasicWorld(sim) # create robot robot = KukaIIWA(sim) robot.print_info() world.load_robot(robot) # define useful variables for IK dt = 1. / 240 link_id = robot.get_end_effector_ids(end_effector=0) joint_ids = robot.joints # actuated joint damping = 0.01 # for damped-least-squares IK wrt_link_id = -1 # robot.get_link_ids('iiwa_link_1') qIdx = robot.get_q_indices(joint_ids) # define gains kp = 50 # 5 if velocity control, 50 if position control kd = 0 # 2*np.sqrt(kp) # create sphere to follow sphere = world.load_visual_sphere(position=np.array([0.5, 0., 1.]), radius=0.05, color=(1, 0, 0, 0.5)) sphere = Body(sim, body_id=sphere) # set initial joint positions (based on the position of the sphere at [0.5, 0, 1]) robot.reset_joint_states(q=[ 8.84305270e-05, 7.11378917e-02, -1.68059886e-04, -9.71690439e-01, 1.68308810e-05, 3.71467111e-01, 5.62890805e-05
class Environment: def __init__(self, spheres=[[0.09, -0.44, 0.715, 1]], cuboids=None): # Define size of the map self.res = 1. # Initialize XBox controller self.controller = XboxControllerInterface(use_thread=True, verbose=False) # Create simulator self.sim = Bullet() # create world self.world = BasicWorld(self.sim) # create robot self.robot = KukaIIWA(self.sim) # define start/end pt self.start_pt = [-0.75, 0., 0.75] self.end_pt = [0.75, 0., 0.75] # Initialize robot location self.send_robot_to(np.array(self.start_pt), dt=2) # Get via points from user via_pts = self.get_via_pts( ) # [[-0.19, -0.65, 0.77], [0.51, -0.44, 0.58]] self.motion_targets = [self.start_pt] + via_pts + [self.end_pt] def send_robot_to(self, location, dt): start = time.perf_counter() for _ in count(): joint_ids = self.robot.joints link_id = self.robot.get_end_effector_ids(end_effector=0) qIdx = self.robot.get_q_indices(joint_ids) x = self.robot.sim.get_link_world_positions(body_id=self.robot.id, link_ids=link_id) q = self.robot.calculate_inverse_kinematics(link_id, position=location) self.robot.set_joint_positions(q[qIdx], joint_ids) self.world.step() if time.perf_counter() - start >= dt: break def get_via_pts(self): print( "Move green dot to via point. Press 'A' to save. Press 'X' to finish." ) X_desired = [0., 0., 1.3] speed_scale_factor = 0.01 via_pts = [] sphere = None for _ in count(): last_trigger = self.controller.last_updated_button movement = self.controller[last_trigger] if last_trigger == 'LJ': X_desired[0] = X_desired[0] + round(movement[0], 1) * speed_scale_factor X_desired[1] = X_desired[1] + round(movement[1], 1) * speed_scale_factor elif last_trigger == 'RJ': X_desired[2] = X_desired[2] + round(movement[1], 1) * speed_scale_factor elif last_trigger == 'A' and movement == 1: print("Via point added") via_pts.append(X_desired) time.sleep(0.5) elif last_trigger == 'X' and movement == 1: self.world.sim.remove_body(sphere) print("Via point generation complete.") break if sphere: self.world.sim.remove_body(sphere) sphere = self.world.load_visual_sphere(X_desired, radius=0.01, color=(0, 1, 0, 1)) return via_pts
class Robot: def __init__(self, sim, world): self.robot = KukaIIWA(sim) self.world = world # change the robot visual self.robot.change_transparency() self.robot.draw_link_frames(link_ids=[-1, 0]) self.start_pos = np.array([-0.75, 0., 0.75]) self.end_pos = np.array([0.75, 0., 0.75]) self.pid = {'kp': 100, 'kd': 0} self.ee_id = self.robot.get_end_effector_ids(end_effector=0) def send_robot_to(self, location): # define useful variables for IK dt = 1. / 240 link_id = self.robot.get_end_effector_ids(end_effector=0) joint_ids = self.robot.joints # actuated joint # joint_ids = joint_ids[2:] damping = 0.01 # for damped-least-squares IK qIdx = self.robot.get_q_indices(joint_ids) # for t in count(): # get current position in the task/operational space x = self.robot.sim.get_link_world_positions(body_id=self.robot.id, link_ids=link_id) dx = self.robot.get_link_world_linear_velocities(link_id) # Get joint configuration q = self.robot.sim.get_joint_positions(self.robot.id, self.robot.joints) # Get linear jacobian if self.robot.has_floating_base(): J = self.robot.get_linear_jacobian(link_id, q=q)[:, qIdx + 6] else: J = self.robot.get_linear_jacobian(link_id, q=q)[:, qIdx] # Pseudo-inverse Jp = self.robot.get_damped_least_squares_inverse(J, damping) # evaluate damped-least-squares IK dq = Jp.dot(self.pid['kp'] * (location - x) - self.pid['kd'] * dx) # set joint velocities # robot.set_joint_velocities(dq) # set joint positions q = q[qIdx] + dq * dt self.robot.set_joint_positions(q, joint_ids=joint_ids) return x def go_home(self): for t in count(): x = self.send_robot_to(self.start_pos) # step in simulation self.world.step() # Check if robot has reached the required position error = np.linalg.norm(self.start_pos - x) if error < 0.01 or t > 500: break def go_to_end(self): self.send_robot_to(self.end_pos)
damping = 0.01 # for damped-least-squares IK wrt_link_id = -1 # robot.get_link_ids('iiwa_link_1') chain_name = robot.get_link_names(joint_ids) # desired position xd = np.array([0.5, 0., 0.5]) world.load_visual_sphere(xd, radius=0.05, color=(1, 0, 0, 0.5)) # joint_ids = joint_ids[2:] # print information about the robot print("") print("Robot: {}".format(robot)) print("Number of DoFs: {}".format(robot.num_dofs)) print("Joint ids: {}".format(robot.joints)) print("Q Indices: {}".format(robot.get_q_indices())) print("Actuated joint ids: {}".format(robot.joints)) print("Link names: {}".format(robot.get_link_names(robot.joints))) print("End-effector names: {}".format( robot.get_link_names(robot.get_end_effector_ids()))) print("Floating base? {}".format(robot.has_floating_base())) print("Total mass = {} kg".format(robot.mass)) print("") print("Base name for IK: {}".format(base_name)) print("Link name for IK: {}".format(end_effector_name)) print("Chain: {}".format(chain_name)) print("") robot.change_transparency() robot.draw_link_frames([-1, 0]) robot.draw_bounding_boxes(joint_ids[0])