evasdk package

Submodules

evasdk.Eva module

class evasdk.Eva.Eva(host_ip, token, request_timeout=5, renew_period=1200)

Bases: object

The Eva class represents a self updating snapshot of Eva at any one time. Once initialised Eva connects to Eva via a websocket and keeps the current state of the robot using the websocket update messages.

api_call_no_auth(method: str, path: str, payload: Optional[dict] = None, headers: dict = {}, timeout: Optional[int] = None, version: str = 'v1') requests.models.Response

Makes a direct API call to EVA to endpoints that do not require authentication.

Note:

This is used within the SDK and will unlikely be used externally. You should not need to use this.

Args:

method (str): GET, POST, DELETE, etc path (str): URL path of API endpoint payload (dict: optional): dict payload headers (dict: optional): option to add additional headers timeout (int: optional): time to wait in seconds before raising an exception version (str: optional): API server version

Returns:

object: Response object containing results of API call

Raises:

EvaError: If it is not successful TypeError: If missing ‘method’ and/or ‘path’

Example:
>>> eva.api_call_no_auth('GET', 'name')
{'name': 'Cunning Moscow Baker'}
api_call_with_auth(method: str, path: str, payload: Optional[dict] = None, headers: dict = {}, timeout: Optional[int] = None, version: str = 'v1') requests.models.Response

Makes a direct API call to EVA to endpoints that require authentication.

Note:

This is used within the SDK and will unlikely be used externally. You should not need to use this.

Args:

method (str): GET, POST, DELETE, etc path (str): URL path of API endpoint payload (dict: optional): dict payload headers (dict: optional): option to add additional headers timeout (int: optional): time to wait in seconds before raising an exception version (str: optional): API server version

Returns:

object: Response object containing results of API call

Raises:

EvaValidationError: If token is invalid or not present

Example:
>>> eva.api_call_with_auth('GET', 'controls/lock')
{'owner': 'none', 'status': 'unlocked'}
auth_create_session() str

Creates a session token token.

Note:

Should not need to be called as it is handled internally.

Returns:

str: session_token

Raises:

EvaError: If it is not successful

Example:
>>> eva.auth_create_session()
c8c3a36b-4fce-4df2-b795-6bf5629ff48d
auth_invalidate_session() None

Deletes/invalidates the API session token.

Raises:

EvaError: If it is not successful

Returns:

None

auth_renew_session() None

Renews the authenticated session token.

Note:

Should not need to be called as it is handled automatically whenever an api_call_with_auth() is used.

Returns:

None

Raises:

EvaError: If it is not successful

calc_forward_kinematics(joints: list, fk_type: Optional[str] = None, tcp_config: Optional[dict] = None) Dict[str, Any]

Gives the position of the robot and orientation of end-effector in 3D space.

Args:

joints (list): a list of joint angles in RADIANS fk_type (str): deprecated for 5.0.0 tcp_config (dict, optional): dict containing TCP configuration

Returns:

dict: containing ‘result’ value, ‘position’ dict, and ‘orientation’ dict

Raises:

EvaError: If it is not successful

Example:
>>> eva.calc_forward_kinematics([0,0,0,0,0,0])
{'result': 'success', 'position': {'x': -0.065000005, 'y': -8.960835e-09, 'z': 0.87839997},
'orientation': {'w': 1, 'x': 0, 'y': 0, 'z': 0}}
calc_inverse_kinematics(guess: list, target_position: dict, target_orientation: dict, tcp_config: Optional[dict] = None, orientation_type: Optional[str] = None) List[float]

Gives a list of joint angles calculated from XYZ and end-effector orientation coordinates.

Args:

guess (list): a list of joing angles in RADIANS near the area of operation target_position (dict): dict containing XYZ coordinates target_orientation (dict): dict containing WYZ (yaw, pitch, roll) of the end effector orientation tcp_config (dict: optional): dict containing TCP configuration. orientation_type (str: optional): ‘matrix’, ‘axis_angle’, ‘euler_zyx’, or ‘quat’(default) orientation types

Returns:

list: containing joint angles if successful

Raises:

EvaError: If it is not successful

Example:
>>> eva_position = {'x': -0.065000005, 'y': -8.960835e-09, 'z': 0.87839997}
>>> eva_orientation = {'w': 1, 'x': 0, 'y': 0, 'z': 0}
>>> eva_guess = [0, 0, 0, 0, 0, 0]
>>> robot.calc_inverse_kinematics(eva_guess, eva_position, eva_orientation)
[0, 0, 0, 0, 0, 0]
calc_nudge(joints: list, direction: str, offset: float, tcp_config: Optional[dict] = None) List[float]

Calculates joint angles required to move robot a certain distance in XYZ space.

Raises:

EvaError: If it is not successful

Args:

joints (list): a list of joint angles in RADIANS direction (str): ‘x’, ‘y’ or ‘z’ axis to move on offset (float): distance in METERS to move tcp_config (dict: optional): dict containing TCP configuration

Returns:

list: calculated joint angles to fulfill direction + offset

Example:
>>> eva_tcp = {"offsets": {"x": 0, "y": 0, "z": 0.1},
>>>            "radius": 0.07,
>>>            "rotations": {"x": 0, "y": 0, "z": 0}}
>>> robot.calc_nudge(eva_guess, direction='y', offset=0.1, tcp_config=eva_tcp)
[-0.36749756, 0.21934654, -0.35547766, -3.8155076e-06, 0.13613085, 0.3675014]
calc_pose_valid(joints: list, tcp_config: Optional[dict] = None) bool

Checks whether requested joint angles are able to be reached successfully.

Args:

joints (list): a list of joint angles in RADIANS tcp_config (dict: optional): dict containing TCP configuration

Returns:

bool: True or False condition

Raises:

EvaError: If it is not successful

Example:
>>> eva_tcp = {"offsets": {"x": 0, "y": 0, "z": 0.1},
>>>            "radius": 0.07,
>>>            "rotations": {"x": 0, "y": 0, "z": 0}}
>>> eva.calc_pose_valid([0,0,0,1.7,0.5,-1], tcp_config=eva_tcp)
True
calc_rotate(joints: list, axis: str, offset: float, tcp_config: Optional[dict] = None) List[float]

Calculates joint angles required to rotate end-effector in a given direction.

Args:

joints (list): a list of joint angles in RADIANS axis (str): ‘x’, ‘y’ or ‘z’ axis to rotate on offset (float): distance in METERS to move tcp_config (dict: optional): dict containing TCP configuration

TCP is considered to be the end-effector of the Robot.

Returns:

list: containing joint angles

Raises:

EvaError: If it is not successful

Example:
>>> eva_tcp = {"offsets": {"x": 0, "y": 0, "z": 0.1},
>>>            "radius": 0.07,
>>>            "rotations": {"x": 0, "y": 0, "z": 0}}
>>> robot.calc_rotate([0, 0, 0, 0, 0, 0], axis='y', offset=0.1, tcp_config=eva_tcp)
[-2.1625242e-09, -0.012081009, 0.09259305, 3.102962e-09, -0.1803575, -5.4273075e-09]
config_update(update: _io.BytesIO) None

Applies choreograph update file to robot.

Note:

Requires the lock. See example.

Args:

update: AUT / update file

Returns:

None

Raises:

EvaError: If it is not successful

Example:
>>> with open("rel-4.10.0.aup", 'rb') as update_file:
>>>     with eva.lock():
>>>         eva.config_update(update_file)
control_acknowledge_collision(wait_for_ready: bool = True) None

Acknowledges collision incident and sets the robot to READY state.

Note:

Requires lock.

Args:

wait_for_ready (bool): boolean value to wait for the robot state to enter READY before proceeding

Returns:

None

Raises:

EvaError: If it is not successful EvaLockError: If you do not own the lock when calling the function

Example:
>>> with eva.lock():
>>>     eva.control_acknowledge_collision()
control_cancel(wait_for_ready: bool = True) None

Cancels PAUSED state, robot will enter READY state after function call.

Note:

Requires lock. Robot will need to be sent home before re-starting a toolpath.

Returns:

None

Args:

wait_for_ready (bool): boolean value to wait for the robot state to enter READY before proceeding

Raises:

EvaError: If it is not successful EvaLockError: If you do not own the lock when calling the function

Example:
>>> with eva.lock():
>>>     eva.control_cancel()
control_configure_collision_detection(enabled: bool, sensitivity: str) None

Sets the sensitivity of the collision detection feature.

Note:

Requires lock.

Args:

enabled (bool): True or False sensitivity (str): ‘low’, ‘medium’ or ‘high’ options of sensitivity

Returns:

None

Raises:

EvaError: If it is not successful ValueError: If sensitivity or enabled arguments are not valid EvaLockError: If you do not own the lock when calling the function

Example:
>>> with eva.lock():
>>>     control_configure_collision_detection(True, 'medium')
control_go_to(joints: list, wait_for_ready: bool = True, max_speed: Optional[float] = None, time_sec: Optional[int] = None, mode: str = 'teach') None

Move robot to specified joint angles.

Note:

Requires lock.

Args:

joints (list): list of angles in RADIANS wait_for_ready (bool): boolean value to wait for the robot state to enter READY before proceeding max_speed (float): maximum speed in m/s when moving to the joint angles. Cannot be used with time_sec time_sec (int): time in seconds of duration to travel to joint angles specified. Cannot be used with max_speed mode (str): ‘teach’ by default, ‘automatic’ must be set for max_speed & time_sec to work

Returns:

None

Raises:

EvaError: If it is not successful,such as exceeding joint angle limits,or using both max_speed and time_sec EvaLockError: If you do not own the lock when calling the function

Example:
>>> with eva.lock():
>>>     control_go_to([0, 0, 0, 0, 0, 0], wait_for_ready=False, max_speed=0.25, mode='automatic')
control_home(wait_for_ready: bool = True) None

Sends robot to home position of the active toolpath.

Note:

Requires lock.

Args:

wait_for_ready (bool): boolean value to wait for the robot to entry READY state before proceeding

Returns:

None

Raises:

EvaError: If it is not successful

Example:
>>> with eva.lock():
>>>     eva.control_home()
control_pause(wait_for_paused: bool = True) None

Pauses robot while in operation.

Note:

Requires lock. Robot MUST be in running state when this is called.

Args:

wait_for_paused (bool): boolean value to wait for the robot to enter PAUSED state before proceeding

Returns:

None

Raises:

EvaError: If it is not successful, such as if the robot is not in the RUNNING state EvaLockError: If you do not own the lock when calling the function

Example:
>>> with eva.lock():
>>>     eva.control_pause()
control_reset_errors(wait_for_ready: bool = True) None

Resets state of the robot to READY.

Note:

Requires lock. An exception will be raised if no errors are present.

Args:

wait_for_ready (bool): boolean value to wait for the robot state to enter READY before proceeding

Returns:

None

Raises:

EvaError: If it is not successful EvaLockError: If you do not own the lock when calling the function

Example:
>>> with eva.lock():
>>>     eva.control_reset_errors()
control_resume(wait_for_running: bool = True) None

Continues robot operation from PAUSED state.

Note:

Requires lock.

Args:

wait_for_running (bool): boolean value to wait for the robot state to enter RUNNING before proceeding

Returns:

None

Raises:

EvaError: If it is not successful EvaLockError: If you do not own the lock when calling the function

Example:
>>> with eva.lock():
>>>     eva.control_resume()
control_run(loop: int = 1, wait_for_ready: bool = True, mode: str = 'teach') None

Runs active toolpath for specified amount of loops.

Note:

Requires lock. Teach mode is active by default, automatic mode must be specified for normal operation.

Args:

loop (int): integer, number of loops to run toolpath for. 0 loops for continuous operation. wait_for_ready (bool): boolean value to wait for the robot state to enter READY before proceeding mode (str): ‘teach’ or ‘automatic’, set to automatic for normal operation

Returns:

None

Raises:

EvaError: If it is not successful

Example:
>>> with eva.lock():
>>>     eva.control_run(5, wait_for_ready=False, mode='automatic')
control_stop_loop(wait_for_ready: bool = True) None

Stops robot once it has reached the end of the current running loop.

Note:

Requires lock.

Args:

wait_for_ready (bool): boolean value to wait for the robot state to enter READY before proceeding

Returns:

None

Raises:

EvaError: If it is not successful EvaLockError: If you do not own the lock when calling the function

Example:
>>> with eva.lock():
>>>     eva.control_stop_loop()
control_wait_for(goal: Union[str, enumerate]) None

Waits for the robot to enter a state specified in RobotState.

Note:

Check RobotState enum (robot_state.py) for list of states.

Args:

goal (str or enumerate): State to wait for before returning

Raises:

EvaError: If the robot enters the ERROR or COLLISION state ValueError: If an invalid state is entered

Returns:

None

Example:
>>> eva.control_wait_for(goal=RobotState.READY)
control_wait_for_ready() None

Waits for the robot to enter the “ready” (RobotState.READY) state.

Returns:

None

Raises:

EvaError: If the robot enters the ERROR or COLLISION state

data_servo_positions() List[float]

Returns a list of current joint angles in radians.

Note:

This function uses the data_snapshot_property() to return the servo positions from the data_snapshot() function.

Returns:

list: list of 6 joint angles in radians

Raises:

EvaError: If the property is not found within the data_snapshot() dict

Example:
>>> eva.data_servo_positions()
[-0.004506206139, 0.20661434531, -0.441608190, -0.00038350690, -1.9729512929, 2.1852223873]
data_snapshot() Dict[str, Any]

Returns a nested dictionary of the status of the robot.

Returns:

dict: Multiple nested dictionary

Raises:

EvaError: If it is not successful

data_snapshot_property(prop: str) Dict[str, Any]

Returns a property from the data_snapshot dict.

Args:

prop (str): property within the data_snapshot() nested dictionary

Returns:

dict: dictionary object specified

Raises:

EvaError: If the property is not found within the data_snapshot() dict

Example:
>>> eva.data_snapshot_property('control')
{'loop_count': 0, 'loop_target': 0, 'run_mode': 'not_running', 'state': 'error'}
globals_edit(keys: str, values: Union[bool, float, str]) dict

Allows editing of exposed global values.

Note:

This is not used directly within the SDK.

Args:

keys (str): a list of keys to change values (Any): a list of the associated values to change global to

Returns:

dict: of the data requested

Raises:

EvaError: If it is not successful

gpio_get(pin: str, pin_type: str) Union[bool, float]

Gets the state of output/input pin.

Args:

pin (str): name of the pin pin_type (str): input or output pin type

Returns:

bool or float: depending on pin_type

Raises:

EvaError: gpio_get error, no such pin (if the pin does not exist) EvaError: gpio_get error, pin_type must be “input” or “output”

Example:
>>> robot.gpio_get('d0', 'output')
True
>>> robot.gpio_get('a0', 'input')
0.018
gpio_set(pin: str, status: Union[bool, str]) None

Changes the state of the output pin.

Note:

Requires the lock. See example.

Args:

pin (str): output pin name that is being changed status (bool or str): state requested.

Returns:

None

Raises:

EvaError: If it is not successful, EvaLockError: If you do not own the lock when calling the function

Example:
>>> with eva.lock():
>>>     robot.gpio_set('d0', True)
lock(wait: bool = True, timeout: Optional[int] = None) evasdk.Eva.Eva

Owns the lock/control of the robot.

Note:

This is best called using the “with eva.lock():” method.

Args:

wait (bool): True/False to wait for lock availability timeout (int): time in seconds to wait for lock availability

Returns:

Eva: evasdk.Eva object

Raises:

EvaError: If it is not successful or if another user owns the lock

Example:
>>> with eva.lock():
>>>     eva.control_reset_errors()
lock_renew() None

Renews the lock session.

Note:

This will need to be called if you do not use the “with eva.lock():” method. If you are handling the lock directly then you must renew the session before the timeout that was set.

Returns:

None

Raises:

EvaError: If it is not successful EvaAdminError: If you do not own the lock

lock_status() Dict[str, str]

Indicates status and owner of the lock.

Raises:

EvaError: If it is not successful

Returns:

dict: containing lock user/owner & status of the lock

Example:
>>> eva.lock_status()
{'owner': 'none', 'status': 'unlocked'}
name() Dict[str, str]

Gets the name of the robot.

Returns:

dict: robot name

Example:
>>> eva.name()
{'name': 'Cunning Moscow Baker'}
set_request_timeout(request_timeout: int) None

Sets default request timeout for API commands.

Args:

request_timeout (int): time in seconds

Returns:

None

toolpaths_delete(toolpathId: int) None

Deletes a toolpath specified from the toolpaths stored on the robot.

Args:

toolpathId (int): toolpathId integer of the toolpath from the toolpaths list

Returns:

None

toolpaths_list() List[dict]

Gets a list of saved toolpaths on the robot.

Returns:

list: a list of dictionaries containing toolpath id, name, and hash

Raises:

EvaError: If it is not successful

Example:
>>> eva.toolpaths_list()
[{'id': 1, 'name': 'test_1', 'hash': 'cacc3c5ca8ada838ee86f703487151edcbae4b9177cf138c8908d12b614b6313'},
{'id': 2, 'name': 'test_2', 'hash': '9bedb2a17cfc965d8a208c2697fee1a5455c558ec8e5aadb2ce4b20dfa016363'}]
toolpaths_retrieve(ID: int) Dict[str, Any]

Retrieves the toolpath using toolpath ID on the robot.

Args:

ID (int): id integer of the toolpath called upon

Returns:

dict: of the toolpath requested

Raises:

EvaError: If it is not successful

Example:
>>> eva.toolpath_retrieve(1)
{'id': 1, 'name': 'test_1', 'hash': 'cacc3c5ca8ada838ee86f703487151edcbae4b9177cf138c8908d12b614b6313',
'toolpath': {'metadata': {'version': 2, 'default_max_speed': 0.25, 'next_label_id': 2,
'analog_modes': {'i0': 'voltage', 'i1': 'voltage', 'o0': 'voltage', 'o1': 'voltage'}, 'payload': 0},
'waypoints': [{'joints': [0, 0.5235988, -1.7453293, 0, -1.9198622, 0], 'label_id': 1}],
'timeline': [{'type': 'home', 'waypoint_id': 0}]}}
toolpaths_save(name: str, toolpath: dict) int

Create a new toolpath or update an existing one (if the name is already used).

Args:

name (str): string to assign to the toolpath name toolpath (dict): dictionary formatted toolpath data

Returns:

int: toolpath ID for the newly created or updated toolpath

Raises:

EvaError: If it is not successful

toolpaths_use(toolpathRepr: dict) None

Sets the toolpath passed to it as the active toolpath which can be homed, run, paused, and stopped.

Args:

toolpathRepr (dict): dictionary containing all toolpath data

Returns:

None

Raises:

EvaError: If it is not successful

Note:

This does not save the toolpath to the toolpaths_list on the robot

toolpaths_use_saved(toolpathId: int) None

Sets the active toolpath from the toolpaths_list which can be homed, run, paused, and stopped.

Args:

toolpathId (int): id integer of the toolpath to be used

Returns:

None

Raises:

EvaError: If it is not successful

unlock() None

Closes the lock session cleanly.

Note:

This will need to be called if you do not use the “with eva.lock():” method. If you are handling the lock directly then you must call this before the timeout period has been reached.

Returns:

None

Raises:

EvaError: If it is not successful EvaAdminError: If you do not own the lock

users_get() Dict[str, list]

Returns the list within a dictionary of users.

Returns:

dict: a list of dictionaries containing user id, email, and role.

Raises:

EvaError: If it is not successful

Example:
>>> eva.users_get()
{'users': [{'id': 1, 'email': 'test@automata.tech', 'role': 'admin'},
 {'id': 2, 'email': 'euan@automata.tech', 'role': 'user'}]}
versions() Dict[str, str]

Gets the API versions supported by the server and the Choreograph version installed on the robot.

Returns:

dict: API version supported, robot choreograph version

Raises:

EvaError: If it is not successful

Example:
>>> eva.versions()
{'APIs': ['v1'], 'robot': '4.10.0'}
websocket() evasdk.eva_ws.Websocket

Creates a websocket class to monitor Eva in the background.

Note:

Notifications will be sent from a different thread so you will need to use a mutex or other synchronization mechanisms.

Returns:

class: WebSocket class

Example:
>>> with eva.websocket() as ws:
>>>     ws.register('state_change', print)
>>>     input('press return when you want to stop')

evasdk.EvaDiscoverer module

class evasdk.EvaDiscoverer.DiscoveredEva(name: str, host: str)

Bases: object

connect(token) evasdk.Eva.Eva
host: str
name: str
class evasdk.EvaDiscoverer.EvaDiscoverer(callback: Callable[[str, evasdk.EvaDiscoverer.DiscoveredEva], None], name: Optional[str] = None)

Bases: object

add_service(zeroconf: zeroconf._core.Zeroconf, service_type: str, service_name: str)
remove_service(zeroconf: zeroconf._core.Zeroconf, service_type: str, service_name: str)
evasdk.EvaDiscoverer.discover_evas(callback: Callable[[str, evasdk.EvaDiscoverer.DiscoveredEva], None])

Returns a context that will discovers robots until exited

It will call callback with 2 arguments: the event (either added or removed) and a Discovered Eva object

Note that callback will be called from another thread so you will need to ensure any data accessed there is done in a thread-safe manner

evasdk.EvaDiscoverer.find_eva(name: str, timeout: float = 5)

Blocks for a maximum of timeout seconds and returns a DiscoveredEva if a robot named name was found, or None

evasdk.EvaDiscoverer.find_evas(timeout: float = 5)

Blocks for timeout seconds and returns a dictionary of DiscoveredEva (with their names as key) discovered in that time

evasdk.EvaDiscoverer.find_first_eva(timeout: float = 5)

Blocks for a maximum of timeout seconds and returns a DiscoveredEva if one was found, or None

evasdk.eva_errors module

exception evasdk.eva_errors.EvaAdminError

Bases: evasdk.eva_errors.EvaError, Exception

Error thrown when request requires admin user rights

exception evasdk.eva_errors.EvaAuthError

Bases: evasdk.eva_errors.EvaError, Exception

Error thrown when request requires authentication

exception evasdk.eva_errors.EvaAutoRenewError

Bases: evasdk.eva_errors.EvaError, Exception

Error thrown when automatic session renewal fails but not the original request

exception evasdk.eva_errors.EvaDisconnectionError

Bases: evasdk.eva_errors.EvaError, Exception

Error thrown when Eva websocket connection is closed

exception evasdk.eva_errors.EvaError

Bases: Exception

Base class for all Eva errors

exception evasdk.eva_errors.EvaLockError

Bases: evasdk.eva_errors.EvaError, Exception

Error thrown when Eva has robot lock issues

exception evasdk.eva_errors.EvaServerError

Bases: evasdk.eva_errors.EvaError, Exception

Error thrown when Eva returns an internal server error

exception evasdk.eva_errors.EvaValidationError

Bases: evasdk.eva_errors.EvaError, ValueError

Error thrown when the request arguements are invalid

exception evasdk.eva_errors.EvaWebsocketError

Bases: evasdk.eva_errors.EvaError, Exception

Error thrown when an issue related to the websocket stream happens

evasdk.eva_errors.eva_error(label, r=None)

evasdk.eva_http_client module

class evasdk.eva_http_client.EvaHTTPClient(host_ip, api_token, custom_logger=None, request_timeout=5, renew_period=1200)

Bases: object

api_call_no_auth(method, path, payload=None, **kwargs)
api_call_with_auth(*args, **kwargs)
api_versions()
auth_create_session()
auth_invalidate_session()
auth_renew_session()
calc_forward_kinematics(joints, fk_type=None, tcp_config=None)
calc_inverse_kinematics(guess, target_position, target_orientation, tcp_config=None, orientation_type=None)

End-effector orientation (target_orientation) can be provided in several standard formats, by specifying the orinetation_type (default is None): - ‘matrix’: rotation matrix -> 3x3 array, in row major order - ‘axis_angle’: axis angle -> {‘angle’: float, ‘x’: float, ‘y’: float, ‘z’: float} - ‘euler_zyx’: {yaw, pitch, roll} Euler (Tait-Bryan) angles -> {‘yaw’: float, ‘pitch’: float, ‘roll’: float} - ‘quat’: quaternion -> {‘w’: float, ‘x’: float, ‘y’: float, ‘z’: float} - None: defaults to quaternion Conversion relies on pytransform3d library

calc_nudge(joints, direction, offset, tcp_config=None)
calc_pose_valid(joints, tcp_config=None)
calc_rotate(joints, axis, offset, tcp_config=None)
config_update(update)
control_acknowledge_collision(wait_for_ready=True)

When a collision is encountered, it must be acknowledged before the robot can be reset

control_cancel(wait_for_ready=True)
control_configure_collision_detection(enabled, sensitivity)

Allows toggling on/off and setting the sensitivity of collision detection

control_go_to(joints, wait_for_ready=True, max_speed=None, time_sec=None, mode='teach')
control_home(wait_for_ready=True)
control_pause(wait_for_paused=True)
control_reset_errors(wait_for_ready=True)
control_resume(wait_for_running=True)
control_run(loop=1, wait_for_ready=True, mode='teach')
control_stop_loop(wait_for_ready=True)
control_wait_for(goal, interval_sec=1)

control_wait_for will poll Eva’s state, waiting for Eva to reach the goal state

control_wait_for_ready()

control_wait_for_ready will poll Eva’s state, waiting for Eva to reach “Ready” state

data_servo_positions()
data_snapshot()
data_snapshot_property(prop)
globals_edit(keys, values)
gpio_get(pin, pin_type)
gpio_set(pin, status)
lock_lock()
lock_renew()
lock_status()
lock_unlock()
lock_wait_for(interval_sec=2, timeout=None)
name()
toolpaths_delete(toolpathId)
toolpaths_list()
toolpaths_retrieve(ID)
toolpaths_save(name, toolpathRepr)
toolpaths_use(toolpathRepr)
toolpaths_use_saved(toolpathId)
users_get()

evasdk.eva_locker module

class evasdk.eva_locker.EvaWithLocker(eva, fallback_renew_period=30)

Bases: object

The EvaWithLocker class is used to keep an Eva locked for the entirety of a Python ‘with’ scope. It expects an already locked Eva object to be passed in, and for the duration of the with scope it will renew the lock every <renew_period> seconds.

‘with’ scopes can be nested, with the lock being renewed in a particular scope for the currently set ‘renew_period’ of the locker. At the end of the outer-most scope it will release the lock.

set_renew_period(renew_period=None)

evasdk.eva_ws module

class evasdk.eva_ws.Websocket(url, protocols, timeout=5)

Bases: object

This class creates a context which runs a thread to monitor a websocket in the background. It follows the Observer pattern, which you can use to listen to specific event or all to get all of them. Note: notifications will be sent from a different thread so you will need to use a mutex or other synchronization mechanims.

deregister(event, callback)
register(event, callback)

evasdk.helpers module

evasdk.helpers.strip_ip(host_address)

strip_ip will remove http and ws prefixes from a host address

class evasdk.helpers.threadsafe_object

Bases: object

threadsafe_object is an object wrapped in a mutex for threadsafe getting and setting. Set is a reserved keyword in python so we’ll use update instead.

get()
update(obj)

evasdk.observer module

class evasdk.observer.Subject

Bases: object

deregister(event, callback)
notify(event, *args)
register(event, callback)

evasdk.robot_state module

class evasdk.robot_state.RobotState(value)

Bases: enum.Enum

An enumeration.

BACKDRIVING = 'backdriving'
COLLISION = 'collision'
DISABLED = 'disabled'
ERROR = 'error'
PAUSED = 'paused'
READY = 'ready'
RUNNING = 'running'
SHUTTING_DOWN = 'shutting_down'
STOPPING = 'stopping'
UPDATING = 'updating'

evasdk.version module

class evasdk.version.EvaVersionRequirements(min: str = '3.0.0', max: str = '5.0.0')

Bases: object

Supported software versions of the Eva. Args:

min (str): minimum version of Eva’s software. max (str): maximum version of Eva’s software.

max: str = '5.0.0'
message() str
min: str = '3.0.0'
evasdk.version.compare_version_compatibility(eva_version: str, eva_requirements: evasdk.version.EvaVersionRequirements, sdk_version: str = '0.0.dev0') Optional[str]

Checks to see if the given SDK version is compatible with the given software version of Eva, in order to decipher the compatibility, we pass in a requirement configuration. Pass in sdk_version so that we aren’t reliant upon __version__ and thus tests don’t have to be updated on updating __version__. Args:

eva_version (str): SemVer formated version of Eva software eva_requirements (EvaVersionRequirements): Eva version requirements. sdk_version (str, optional): SemVer formated version of the SDK. Defaults to __version__.

Returns:

str: An error string if there is one, empty implies compatible.

evasdk.version.sdk_is_compatible_with_robot(eva_version: str) Optional[str]

Checks to see if the current version is compatible with the given version of Eva. Args:

eva_version (str): Eva SemVer version.

Returns:

str: An error string if there is one, empty implies compatible.

Module contents

Eva Python SDK

This module provides convenient access to the Automata Eva API from applications written in Python 3.

## Examples

The Eva object allows you to directly control an Eva robot. It provides lots of useful helper function for interacting with the robot.

### Eva

Connecting

```python host = ‘<your_eva_IP_here>’ token = ‘<your_token_here>’

eva = Eva(host, token) ```

GoTo movement

```python eva = Eva(host_ip, token)

with eva.lock():

eva.control_wait_for_ready() eva.control_go_to([0, 0, 0, 0, 0, 0], mode=’teach’)

```

Toolpath create and run

```python toolpath = {

“metadata”:{

“default_velocity”:0.7, “next_label_id”:5, “analog_modes”:{ “i0”:”voltage”, “i1”:”voltage”, “o0”:”voltage”, “o1”:”voltage” }

}, “waypoints”:[

{ “joints”:[-0.68147224, 0.3648368, -1.0703622, 9.354615e-05, -2.4358354, -0.6813218], “label_id”:3 }, { “joints”:[-0.6350288, 0.25192022, -1.0664424, 0.030407501, -2.2955494, -0.615318], “label_id”:2 }, { “joints”:[-0.13414459, 0.5361486, -1.280493, -6.992453e-08, -2.3972468, -0.13414553], “label_id”:1 }, { “joints”:[-0.4103904, 0.33332264, -1.5417944, -5.380291e-06, -1.9328799, -0.41031334], “label_id”:4 }

], “timeline”:[

{ “type”:”home”, “waypoint_id”:2 }, { “type”:”trajectory”, “trajectory”:”joint_space”, “waypoint_id”:1 }, { “type”:”trajectory”, “trajectory”:”joint_space”, “waypoint_id”:0 }, { “type”:”trajectory”, “trajectory”:”joint_space”, “waypoint_id”:2 }

]

}

eva = Eva(host, token)

with eva.lock():

eva.control_wait_for_ready() eva.toolpaths_use(toolpath) eva.control_home() eva.control_run(loop=1, mode=’teach’)

```

Please refer to the examples directory for more SDK usage examples.

### evasdk.eva_http and evasdk.eva_ws

These can be used to interact directly with the HTTP and Websocket APIs. Useful when you don’t want the managed websocket connection provided by the evasdk.Eva object.