def eva(ip, token): e = Eva(ip, token, request_timeout=10, renew_period=2 * 60) e._Eva__logger.setLevel(logging.DEBUG) e._Eva__http_client._EvaHTTPClient__logger.setLevel(logging.DEBUG) yield e if e.lock_status()['status'] != 'unlocked': e.unlock()
def test_user_agent(self, **kwargs): eva = Eva("example.com", "NONE") kwargs['mock'].register_uri( 'GET', 'http://example.com/api/versions', request_headers={ 'User-Agent': 'Automata EvaSDK/0.0.dev0 (Python)', }, json={'APIs': ['v1']}, ) versions = eva.versions() assert (versions['APIs'][0] == 'v1')
# 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 print("Waiting for Robot lock") with eva.lock(): print('Eva moving to home position') eva.control_go_to(pose_home)
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 for grid_position in my_test_grid: # Calculate joint angles for the grid position and goto those joint angles print('Eva going to grid position x={:f}, y={:f}'.format(grid_position.x, grid_position.y))
from evasdk import Eva from evaUtilities import EvaGrids from config.config_manager import load_use_case_config if __name__ == "__main__": # Load use-case parameters config = load_use_case_config() # Connection to robot host = config['EVA']['comm']['host'] token = config['EVA']['comm']['token'] eva = Eva(host, token) # Compute grid points and robot joints eva_box = EvaGrids(eva, config, show_plot=True) joints = eva_box.get_grid_points(config['grids']['names']) # Go home before starting with eva.lock(): eva.control_go_to(config['EVA']['home']) while True: for counter in range(len(joints[(config['grids']['names'][0])]['pick'])): joints_home = config['EVA']['home'] joints_pick = joints[config['grids']['names'][0]]['pick'][counter] joints_drop = joints[config['grids']['names'][1]]['pick'][counter] joints_pick_hover = joints[config['grids']['names'][0]]['hover'][counter] joints_drop_hover = joints[config['grids']['names'][1]]['hover'][counter] # USER DEFINED WAY-POINTS
#!/usr/bin/env python3 from evasdk import Eva # This example shows usage of the eva_ws and eva_http modules, used for direct control # using the network interfaces. eva_http also contains some helper functions not # contained in the public API, such as lock_wait_for. host_ip = input("Please enter a Eva IP: ") token = input("Please enter a valid Eva token: ") print(f'ip: [{host_ip}], token: [{token}]\n') eva = Eva(host_ip, token) users = eva.users_get() print(f'Eva at {host_ip} users: {users}\n') joint_angles = eva.data_servo_positions() print(f'Eva current joint angles: {joint_angles}') with eva.websocket() as ws: ws.register('state_change', print) input('press return when you want to stop\n')
#!/usr/bin/env python3 from evasdk import Eva import json # This example shows usage of the Eva object, used for controlling Eva, # reading Eva's current state and responding to different events triggered # by Eva's operation. host_ip = input("Please enter a Eva IP: ") token = input("Please enter a valid Eva token: ") eva = Eva(host_ip, token) # Send Eva to a waypoint with eva.lock(): eva.control_wait_for_ready() eva.control_go_to([0, 0, 0, 0, 0, 0]) # Print Eva's toolpaths toolpaths = eva.toolpaths_list() outToolpaths = [] for toolpathItem in toolpaths: toolpath = eva.toolpaths_retrieve(toolpathItem['id']) outToolpaths.append(toolpath) print(json.dumps(outToolpaths)) # Create a basic toolpath and execute it toolpath = { "metadata": { "version": 2,