Skip to content

Commit 349ef0c

Browse files
committed
Add RMD motor UI
1 parent 813867d commit 349ef0c

File tree

3 files changed

+365
-0
lines changed

3 files changed

+365
-0
lines changed

main.py

+6
Original file line numberDiff line numberDiff line change
@@ -513,6 +513,12 @@ def update_tabs_cb(active):
513513
self.effects_graph_dlg.setEnabled(True)
514514
self.actionEffectsMonitor.setEnabled(True)
515515
self.actionEffects_forces.setEnabled(True)
516+
elif classe_active["id"] == 0x8B or classe_active["id"] == 0x8C:
517+
classe = rmd_ui.RmdUI(main=self, unique=classe_active["unique"])
518+
name_axis = classe_active["name"]
519+
self.active_classes[name] = classe
520+
self.add_tab(classe, name_axis)
521+
self.profile_ui.set_save_btn(True)
516522

517523

518524

res/rmdmotor.ui

+257
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,257 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<ui version="4.0">
3+
<class>Form</class>
4+
<widget class="QWidget" name="Form">
5+
<property name="geometry">
6+
<rect>
7+
<x>0</x>
8+
<y>0</y>
9+
<width>689</width>
10+
<height>536</height>
11+
</rect>
12+
</property>
13+
<property name="windowTitle">
14+
<string>Form</string>
15+
</property>
16+
<layout class="QGridLayout" name="gridLayout">
17+
<item row="0" column="1">
18+
<widget class="QGroupBox" name="groupBox_2">
19+
<property name="sizePolicy">
20+
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
21+
<horstretch>2</horstretch>
22+
<verstretch>0</verstretch>
23+
</sizepolicy>
24+
</property>
25+
<property name="title">
26+
<string>Info</string>
27+
</property>
28+
<layout class="QGridLayout" name="gridLayout_2">
29+
<item row="1" column="0">
30+
<widget class="QLabel" name="label_4">
31+
<property name="text">
32+
<string>Model:</string>
33+
</property>
34+
</widget>
35+
</item>
36+
<item row="0" column="0">
37+
<widget class="QLabel" name="label_6">
38+
<property name="text">
39+
<string>Voltage:</string>
40+
</property>
41+
</widget>
42+
</item>
43+
<item row="1" column="1">
44+
<widget class="QLabel" name="label_model">
45+
<property name="frameShape">
46+
<enum>QFrame::StyledPanel</enum>
47+
</property>
48+
<property name="text">
49+
<string/>
50+
</property>
51+
</widget>
52+
</item>
53+
<item row="0" column="1">
54+
<widget class="QLabel" name="label_voltage">
55+
<property name="frameShape">
56+
<enum>QFrame::StyledPanel</enum>
57+
</property>
58+
<property name="text">
59+
<string>Not available</string>
60+
</property>
61+
</widget>
62+
</item>
63+
<item row="2" column="0">
64+
<widget class="QLabel" name="label_7">
65+
<property name="text">
66+
<string>Errors:</string>
67+
</property>
68+
<property name="alignment">
69+
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
70+
</property>
71+
</widget>
72+
</item>
73+
<item row="2" column="1">
74+
<widget class="QLabel" name="label_errornames">
75+
<property name="frameShape">
76+
<enum>QFrame::StyledPanel</enum>
77+
</property>
78+
<property name="text">
79+
<string>None</string>
80+
</property>
81+
<property name="alignment">
82+
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
83+
</property>
84+
</widget>
85+
</item>
86+
</layout>
87+
</widget>
88+
</item>
89+
<item row="4" column="0" colspan="2">
90+
<widget class="QGroupBox" name="groupBox_3">
91+
<property name="sizePolicy">
92+
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
93+
<horstretch>2</horstretch>
94+
<verstretch>1</verstretch>
95+
</sizepolicy>
96+
</property>
97+
<property name="title">
98+
<string>Help</string>
99+
</property>
100+
<layout class="QVBoxLayout" name="verticalLayout">
101+
<item>
102+
<widget class="QTextBrowser" name="textBrowser">
103+
<property name="html">
104+
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
105+
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
106+
p, li { white-space: pre-wrap; }
107+
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&gt;
108+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;This controls a MyActuator RMD motor via CAN bus.&lt;/p&gt;
109+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;It is recommended to use not more than 250Hz FFB update rates due to the slow packet rates of the motor driver.&lt;/p&gt;
110+
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
111+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; text-decoration: underline;&quot;&gt;Setup:&lt;/span&gt;&lt;/p&gt;
112+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Enable fault status sending and set the CAN id and CAN rate in the motor.&lt;/p&gt;
113+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;1M baud is recommended.&lt;/p&gt;
114+
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
115+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; text-decoration: underline;&quot;&gt;Active requests &amp;amp; Interpolation:&lt;/span&gt;&lt;/p&gt;
116+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;The motor can either send positions at a fixed 10ms interval (active requests off) or the FFBoard can actively request positions and use the low resolution torque reply status for interpolation.&lt;/p&gt;
117+
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
118+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; text-decoration: underline;&quot;&gt;Active requests off (high resolution)&lt;/span&gt;:&lt;/p&gt;
119+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;The motor sends the position every 10ms using the active reply function. &lt;/p&gt;
120+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Reduces the overhead and jitter.&lt;br /&gt;Recommended for multi motor systems and shared CAN bus.&lt;/p&gt;
121+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Status info is not available. Active reply mode disables all replies.&lt;/p&gt;
122+
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
123+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; text-decoration: underline;&quot;&gt;Active requests on (low resolution)&lt;/span&gt;:&lt;/p&gt;
124+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;FFBoard actively requests positions and uses low resolution 1° torque status replies for interpolation. Status info is available.&lt;/p&gt;
125+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;May cause jitter in time and position, significant bus traffic.&lt;/p&gt;
126+
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
127+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; text-decoration: underline;&quot;&gt;Torque:&lt;/span&gt;&lt;/p&gt;
128+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Enter the maximum current of the motor to scale the available range.&lt;/p&gt;
129+
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
130+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; text-decoration: underline;&quot;&gt;CAN speeds:&lt;/span&gt;&lt;/p&gt;
131+
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;1Mbit/s is recommended and must match the setting in the motor.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
132+
</property>
133+
</widget>
134+
</item>
135+
</layout>
136+
</widget>
137+
</item>
138+
<item row="2" column="1">
139+
<spacer name="verticalSpacer">
140+
<property name="orientation">
141+
<enum>Qt::Vertical</enum>
142+
</property>
143+
<property name="sizeHint" stdset="0">
144+
<size>
145+
<width>0</width>
146+
<height>0</height>
147+
</size>
148+
</property>
149+
</spacer>
150+
</item>
151+
<item row="1" column="1">
152+
<spacer name="verticalSpacer_2">
153+
<property name="orientation">
154+
<enum>Qt::Vertical</enum>
155+
</property>
156+
<property name="sizeHint" stdset="0">
157+
<size>
158+
<width>0</width>
159+
<height>0</height>
160+
</size>
161+
</property>
162+
</spacer>
163+
</item>
164+
<item row="0" column="0" rowspan="2">
165+
<widget class="QGroupBox" name="groupBox">
166+
<property name="sizePolicy">
167+
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
168+
<horstretch>0</horstretch>
169+
<verstretch>0</verstretch>
170+
</sizepolicy>
171+
</property>
172+
<property name="title">
173+
<string>Settings</string>
174+
</property>
175+
<layout class="QFormLayout" name="formLayout">
176+
<item row="0" column="0">
177+
<widget class="QLabel" name="label_2">
178+
<property name="text">
179+
<string>CAN speed</string>
180+
</property>
181+
</widget>
182+
</item>
183+
<item row="1" column="0">
184+
<widget class="QLabel" name="label">
185+
<property name="text">
186+
<string>Max torque range</string>
187+
</property>
188+
</widget>
189+
</item>
190+
<item row="1" column="1">
191+
<widget class="QDoubleSpinBox" name="doubleSpinBox_torque">
192+
<property name="suffix">
193+
<string>A</string>
194+
</property>
195+
<property name="maximum">
196+
<double>300.000000000000000</double>
197+
</property>
198+
<property name="singleStep">
199+
<double>0.010000000000000</double>
200+
</property>
201+
</widget>
202+
</item>
203+
<item row="3" column="0">
204+
<widget class="QPushButton" name="pushButton_apply">
205+
<property name="text">
206+
<string>Submit</string>
207+
</property>
208+
</widget>
209+
</item>
210+
<item row="2" column="0">
211+
<widget class="QLabel" name="label_5">
212+
<property name="text">
213+
<string>CAN ID</string>
214+
</property>
215+
</widget>
216+
</item>
217+
<item row="2" column="1">
218+
<widget class="QSpinBox" name="spinBox_id">
219+
<property name="prefix">
220+
<string>0x140+</string>
221+
</property>
222+
<property name="minimum">
223+
<number>1</number>
224+
</property>
225+
<property name="maximum">
226+
<number>32</number>
227+
</property>
228+
<property name="singleStep">
229+
<number>1</number>
230+
</property>
231+
</widget>
232+
</item>
233+
<item row="0" column="1">
234+
<widget class="QPushButton" name="pushButton_cansettings">
235+
<property name="text">
236+
<string>Change CAN settings</string>
237+
</property>
238+
</widget>
239+
</item>
240+
<item row="3" column="1">
241+
<widget class="QCheckBox" name="checkBox_activerequests">
242+
<property name="toolTip">
243+
<string>Stores and reloads absolute encoder offset at startup for centering</string>
244+
</property>
245+
<property name="text">
246+
<string>Active requests/High speed position mode</string>
247+
</property>
248+
</widget>
249+
</item>
250+
</layout>
251+
</widget>
252+
</item>
253+
</layout>
254+
</widget>
255+
<resources/>
256+
<connections/>
257+
</ui>

rmd_ui.py

+102
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,102 @@
1+
from PyQt6.QtWidgets import QMainWindow
2+
from PyQt6.QtWidgets import QDialog
3+
from PyQt6.QtWidgets import QWidget
4+
from PyQt6.QtWidgets import QMessageBox,QVBoxLayout,QCheckBox,QButtonGroup
5+
from PyQt6 import uic
6+
from helper import res_path,classlistToIds
7+
from PyQt6.QtCore import QTimer
8+
import main
9+
from base_ui import WidgetUI
10+
from base_ui import CommunicationHandler
11+
import portconf_ui
12+
13+
class RmdUI(WidgetUI,CommunicationHandler):
14+
ERRORS = {"Stall" : 0x02,"Undervoltage" : 0x04, "Overvoltage" : 0x08,"Overcurrent" : 0x10, "Overpower" : 0x40,"Write err" : 0x80,"Overspeed" : 0x100,"Overtemperature": 0x10000,"Calibration error" : 0x2000}
15+
16+
17+
def __init__(self, main=None, unique=None):
18+
WidgetUI.__init__(self, main,'rmdmotor.ui')
19+
CommunicationHandler.__init__(self)
20+
self.main = main #type: main.MainUi
21+
22+
self.timer = QTimer(self)
23+
self.canOptions = portconf_ui.CanOptionsDialog(0,"CAN",main)
24+
self.pushButton_apply.clicked.connect(self.apply)
25+
self.pushButton_cansettings.clicked.connect(self.canOptions.exec)
26+
self.timer.timeout.connect(self.updateTimer)
27+
self.prefix = unique
28+
self.connected = False
29+
self.activepos = True
30+
31+
self.register_callback("rmd","canid",self.spinBox_id.setValue,self.prefix,int)
32+
self.register_callback("rmd","maxtorque",self.updateTorque,self.prefix,int)
33+
self.register_callback("rmd","vbus",self.voltageCb,self.prefix,int)
34+
self.register_callback("rmd","errors",lambda v : self.showErrors(v),self.prefix,int)
35+
self.register_callback("rmd","model",self.modelcb,self.prefix,str)
36+
self.register_callback("rmd","requestpos",self.requestposcb,self.prefix,int)
37+
38+
self.init_ui()
39+
40+
# Tab is currently shown
41+
def showEvent(self,event):
42+
self.init_ui()
43+
self.timer.start(1000)
44+
45+
# Tab is hidden
46+
def hideEvent(self,event):
47+
self.timer.stop()
48+
49+
def init_ui(self):
50+
commands = ["canid","maxtorque","requestpos","model"]
51+
self.send_commands("rmd",commands,self.prefix)
52+
53+
54+
def modelcb(self,v):
55+
self.label_model.setText(v)
56+
57+
def requestposcb(self,v):
58+
self.checkBox_activerequests.setChecked(v != 0)
59+
self.activepos = v != 0
60+
61+
def updateTorque(self,torque):
62+
self.doubleSpinBox_torque.setValue(torque/100)
63+
64+
def voltageCb(self,v):
65+
if not self.activepos:
66+
self.label_voltage.setText("Not available")
67+
return
68+
self.label_voltage.setText("{}V".format(v/10))
69+
70+
def showErrors(self,codes):
71+
errs = []
72+
if(codes == 0):
73+
errs = ["None"]
74+
75+
for name,i in (self.ERRORS.items()):
76+
if(codes & i != 0):
77+
errs.append(name)
78+
if len(errs) == 0:
79+
errs = [str(codes)]
80+
errString = "\n".join(errs)
81+
82+
self.label_errornames.setText(f"{errString} ({codes})")
83+
84+
def updateTimer(self):
85+
if self.activepos:
86+
self.send_commands("rmd",["vbus","errors"],self.prefix)
87+
else:
88+
self.send_commands("rmd",["errors"],self.prefix)
89+
90+
91+
def apply(self):
92+
canId = str(self.spinBox_id.value())
93+
torqueScaler = str(int(self.doubleSpinBox_torque.value() * 100))
94+
self.send_value("rmd","canid",canId,instance=self.prefix)
95+
self.send_value("rmd","maxtorque",torqueScaler,instance=self.prefix)
96+
self.send_value("rmd","requestpos",1 if self.checkBox_activerequests.isChecked() else 0,instance=self.prefix)
97+
self.activepos = self.checkBox_activerequests.isChecked()
98+
if not self.activepos:
99+
self.voltageCb(0)
100+
101+
self.init_ui() # Update UI
102+

0 commit comments

Comments
 (0)