-
Notifications
You must be signed in to change notification settings - Fork 17
/
main.py
executable file
·161 lines (127 loc) · 6.67 KB
/
main.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
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
#!/usr/bin/env python3
import streamlit as st
import odrive
from odrive.utils import dump_errors
import numpy as np
import pylab as pl
import session
import time
import threading
import odrive_helpers as oh
st.title("ODrive Tuning & Debugging")
@st.cache(allow_output_mutation=True)
def get_odrv():
return odrive.find_any()
odrv = get_odrv()
view = session.get_state()
if view.vbus_voltage is None:
hashable = oh.make_hashable(odrv, 'odrv')
for key in dir(hashable):
if not key.startswith('_'):
setattr(view, key, getattr(hashable, key))
view.torque = [
abs(odrv.axis0.controller.input_torque),
abs(odrv.axis1.controller.input_torque),
]
view.vel = [
abs(odrv.axis0.controller.input_vel),
abs(odrv.axis1.controller.input_vel),
]
view.pos = [
abs(odrv.axis0.controller.input_pos),
abs(odrv.axis1.controller.input_pos),
]
def update():
print('start thread', threading.current_thread().name)
while threading.current_thread() == [ t for t in threading.enumerate() if t.name.startswith('update') ][-1]:
t0 = time.time()
while time.time() < t0 + 1.0:
for key, value in view.data.items():
value.append(oh.rgetattr(odrv, key))
time.sleep(0.02)
for key in view.data:
view.data[key] = view.data[key][-500:]
view.sync()
print('stop thread', threading.current_thread().name)
if view.data is None:
keys = [
'axis0.encoder.pos_estimate',
'axis1.encoder.pos_estimate',
'axis0.controller.input_pos',
'axis1.controller.input_pos',
'axis0.encoder.vel_estimate',
'axis1.encoder.vel_estimate',
'axis0.controller.input_vel',
'axis1.controller.input_vel',
]
view.data = { key: [] for key in keys }
thread = threading.Thread(target=update, daemon=True, name='update_%.3f' % time.time())
thread.start()
cols = st.beta_columns(2)
for a in range(2):
view_axis = view.axis0 if a == 0 else view.axis1
odrv_axis = odrv.axis0 if a == 0 else odrv.axis1
with cols[a]:
st.header(f'Axis {a}')
if odrv_axis.error:
st.write('Error:', hex(odrv_axis.error))
st.subheader('Settings')
oh.number_input(odrv_axis, view_axis, f'controller.config.pos_gain {a}', min_value=0.0)
oh.number_input(odrv_axis, view_axis, f'controller.config.vel_gain {a}', min_value=0.0)
oh.number_input(odrv_axis, view_axis, f'controller.config.vel_integrator_gain {a}', min_value=0.0)
oh.number_input(odrv_axis, view_axis, f'controller.config.vel_limit {a}', min_value=0.0)
oh.number_input(odrv_axis, view_axis, f'encoder.config.bandwidth {a}', min_value=0.0)
st.subheader('Test')
oh.radio(odrv_axis, view_axis, f'controller.config.control_mode {a}', oh.modes)
if oh.modes[view_axis.controller.config.control_mode] == 'torque control':
view.torque[a] = st.number_input(f'input_torque: {view_axis.controller.input_torque}', value=view.torque[a], key=f'torque-{a}')
if abs(view.torque[a]) != abs(view_axis.controller.input_torque):
view_axis.controller.input_torque = odrv_axis.controller.input_torque = view.torque[a] * np.sign(view_axis.controller.input_torque)
oh.setbutton(odrv_axis, view_axis, f'controller.input_torque {a}0', -view.torque[a])
oh.setbutton(odrv_axis, view_axis, f'controller.input_torque {a}1', 0.0)
oh.setbutton(odrv_axis, view_axis, f'controller.input_torque {a}2', view.torque[a])
if oh.modes[view_axis.controller.config.control_mode] == 'position control':
view.pos[a] = st.number_input(f'input_pos: {view_axis.controller.input_pos}', value=view.pos[a], key=f'pos-{a}')
if abs(view.pos[a]) != abs(view_axis.controller.input_pos):
view_axis.controller.input_pos = odrv_axis.controller.input_pos = view.pos[a] * np.sign(view_axis.controller.input_pos)
oh.setbutton(odrv_axis, view_axis, f'controller.input_pos {a}0', -view.pos[a])
oh.setbutton(odrv_axis, view_axis, f'controller.input_pos {a}1', 0.0)
oh.setbutton(odrv_axis, view_axis, f'controller.input_pos {a}2', view.pos[a])
fig, ax = pl.subplots()
pl.tick_params(axis='x', which='both', bottom=False, labelbottom=False)
ax.set_title('position')
ax.plot(view.data[f'axis{a}.encoder.pos_estimate'])
ax.plot(view.data[f'axis{a}.controller.input_pos'])
st.pyplot(fig)
if oh.modes[view_axis.controller.config.control_mode] == 'velocity control':
view.vel[a] = st.number_input(f'input_vel: {view_axis.controller.input_vel}', min_value=0.0, value=view.vel[a], key=f'vel-{a}')
if abs(view.vel[a]) != abs(view_axis.controller.input_vel):
view_axis.controller.input_vel = odrv_axis.controller.input_vel = view.vel[a] * np.sign(view_axis.controller.input_vel)
oh.setbutton(odrv_axis, view_axis, f'controller.input_vel {a}0', -view.vel[a])
oh.setbutton(odrv_axis, view_axis, f'controller.input_vel {a}1', 0.0)
oh.setbutton(odrv_axis, view_axis, f'controller.input_vel {a}2', view.vel[a])
fig, ax = pl.subplots()
pl.tick_params(axis='x', which='both', bottom=False, labelbottom=False)
ax.set_title('velocity')
ax.plot(view.data[f'axis{a}.encoder.vel_estimate'])
ax.plot(view.data[f'axis{a}.controller.input_vel'])
st.pyplot(fig)
view_axis.current_state = oh.states.index(st.selectbox('state', oh.states, view_axis.current_state, key=f'state-{a}'))
if view_axis.current_state != odrv_axis.current_state:
odrv_axis.requested_state = view_axis.current_state
for state in ['idle', 'closed loop control']:
if oh.states[view_axis.current_state] != state:
if st.button(f'Switch to "{state}" state', key=f'button-{state}-{a}'):
view_axis.current_state = oh.states.index(state)
st.sidebar.header('ODrive')
st.sidebar.write('Serial number:', hex(odrv.serial_number).removeprefix('0x').upper())
st.sidebar.write('Hardware version:', f'{odrv.hw_version_major}.{odrv.hw_version_minor}.{odrv.hw_version_variant}')
st.sidebar.write('Firmware version:', f'{odrv.fw_version_major}.{odrv.fw_version_minor}.{odrv.fw_version_revision}', '(dev)' if odrv.fw_version_unreleased else '')
st.sidebar.write('Voltage:', np.round(odrv.vbus_voltage, 2))
if st.sidebar.button('Clear errors'):
dump_errors(odrv, True)
if st.sidebar.button('Save configuration'):
odrv.save_configuration()
if st.sidebar.button('Reboot'):
odrv.reboot()
view.sync()