forked from automata-tech/eva_python_sdk
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy patheva_example.py
executable file
·55 lines (47 loc) · 1.82 KB
/
eva_example.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
#!/usr/bin/env python3
from automata.Eva import Eva
import time
import json
import logging
# 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":{
"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 }
]
}
with eva.lock():
eva.control_wait_for_ready()
eva.toolpaths_use(toolpath)
eva.control_home()
eva.control_run(loop=1)