# Define the x and y coordinates for 3 corners of the grid grid_corners1: GridCorners = [ XYPoint(x = 0.25, y = 0), # Starting position XYPoint(x = 0.46, y = 0.1), # Length of the grid XYPoint(x = 0.42, y = 0.35), # width of the grid ] # Symmetrical grid grid_corners2: GridCorners = [ XYPoint(x = 0.25, y = 0), XYPoint(x = 0.46,y = -0.1), XYPoint(x = 0.42, y = -0.35), ] # Using the corners and an amount of rows and columns, make the Grid2D my_test_grid1 = Grid2D(grid_corners1, rows = 4, columns = 4) my_test_grid2 = Grid2D(grid_corners2, rows = 4, columns = 4) # Connect to Eva host_ip = "your host" token = "your token" eva = Eva(host_ip, token) # Set some default poses and a default orientation pose_home = [0.057526037, 0.7658633, -1.9867575, 0.026749607, -1.732109, -0.011505207] end_effector_orientation = {'w': 0.0, 'x': 0.0, 'y': 1.0, 'z': 0.0} # Be carefull with this dimension - depending on the type of gripper grid_z_position: float = 0.27
from typing import List, Tuple, NamedTuple import time from evasdk import Eva from grid2d import Grid2D, GridCorners, XYPoint # Define the x and y coordinates for 3 corners of the grid grid_corners: GridCorners = [ XYPoint(x = 0.25, y = 0), XYPoint(x = 0.35, y = 0), XYPoint(x = 0.35, y = 0.4), ] # Using the corners and an amount of rows and columns, make the Grid2D my_test_grid = Grid2D(grid_corners, rows = 4, columns = 4) # Connect to Eva host_ip = input("Please enter a Eva IP: ") token = input("Please enter a valid Eva token: ") eva = Eva(host_ip, token) # Set some default poses and a default orientation pose_home = [0.057526037, 0.7658633, -1.9867575, 0.026749607, -1.732109, -0.011505207] end_effector_orientation = {'w': 0.0, 'x': 0.0, 'y': 1.0, 'z': 0.0} grid_z_position: float = 0.4 print("Waiting for Robot lock") with eva.lock(): print('Eva moving to home position') eva.control_go_to(pose_home) # For each grid position in the Grid2D