-
-
Notifications
You must be signed in to change notification settings - Fork 4
/
demo_dual_motor_rc_hdmi.spin2
394 lines (315 loc) · 15.2 KB
/
demo_dual_motor_rc_hdmi.spin2
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
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
'' =================================================================================================
''
'' File....... demo_dual_motor_rc_hdmi.spin2
'' Purpose.... Demonstrate R/C driving of a two-wheeled platform
'' Authors.... Stephen M Moraco
'' -- Copyright (c) 2023 Iron Sheep Productions, LLC
'' -- see below for terms of use
'' E-mail..... stephen@ironsheep.biz
'' Started.... Mar 2023
'' Updated.... 16 Sep 2023
''
'' =================================================================================================
CON { timing }
CLK_FREQ = 270_000_000 ' system freq as a constant
_clkfreq = CLK_FREQ ' set system clock
CON { fixed io pins }
RX1 = 63 { I } ' programming / debug
TX1 = 62 { O }
SF_CS = 61 { O } ' serial flash
SF_SCK = 60 { O }
SF_SDO = 59 { O }
SF_SDI = 58 { I }
'LA_CHAN0 = 56 { O }
'LA_CHAN1 = 57 { O }
' describe where things are attached to our newer larger edge breakout board (#64029)
SBUS_RX = 58 { I }
HDMI_BASE_PIN = tvDebug.PINS_P0_P7
{
' debug via serial to RPi (using RPi gateway pins)
DEBUG_PIN_TX = 57
DEBUG_PIN_RX = 56
DEBUG_BAUD = 2_000_000
'}
' NOTE: motor pins are set in: isp_bldc_motor_userconfig.spin2
OBJ { our Drive Subsystem }
user : "isp_bldc_motor_userconfig" ' driver configuration
wheels : "isp_steering_2wheel" ' the dual-drive BLDC motors
remoteCtl : "isp_flysky_rx" ' the FlySky Transmitter
tvDebug : "isp_hdmi_debug" ' HDMI debug object
VAR
long remoteCog
DAT { run-time condition vars }
bUseHDMI LONG TRUE ' set to TRUE to enable HDMI use/output
PUB main() | statusOK, basePinLt, basePinRt, voltage, motor, basePin, detectModeLt, detectModeRt
'' DEMO Driving a two wheeled platform
debug("* demo dual motor control via R/C w/HDMI")
if bUseHDMI
basePin := tvDebug.validBasePinForChoice(HDMI_BASE_PIN)
if basePin <> tvDebug.INVALID_PIN_BASE
tvDebug.start(basePin)
debug("* HDMI started")
else
debug("* ERROR bad pin #")
' validate user settings/choicess
' do NOT start motor unless all are legit!
basePinLt := wheels.validBasePinForChoice(user.LEFT_MOTOR_BASE)
basePinRt := wheels.validBasePinForChoice(user.RIGHT_MOTOR_BASE)
detectModeLt := wheels.validDetectModeForChoice(user.LEFT_BOARD_TYPE)
detectModeRt := wheels.validDetectModeForChoice(user.RIGHT_BOARD_TYPE)
voltage := wheels.validVoltageForChoice(user.DRIVE_VOLTAGE)
motor := wheels.validMotorForChoice(user.MOTOR_TYPE)
' repeat
if basePinLt <> wheels.INVALID_PIN_BASE and basePinRt <> wheels.INVALID_PIN_BASE and voltage <> wheels.INVALID_VOLTAGE and motor <> wheels.INVALID_MOTOR and detectModeLt <> wheels.INVALID_DET_MODE and detectModeRt <> wheels.INVALID_DET_MODE
' start our dual motor driver
' start our motor drivers (left and right)
wheels.start(basePinLt, basePinRt, voltage, detectModeLt, detectModeRt)
' override defaults, use 100 %
wheels.setMaxSpeed(100)
wheels.setMaxSpeedForDistance(100)
' just don't draw current at stop
wheels.holdAtStop(false)
if bUseHDMI
connectMotorToHDMI()
' ---- TEST TEST TEST ----
'remoteCtl.manualCalibrate()
'debug("-- HOLD --")
'repeat ' hold here for now
' ---- TEST TEST TEST ----
debug("* Set up - remote control")
remoteCog := remoteCtl.start(SBUS_RX)
statusOK := remoteCog <> 0 ? TRUE : FALSE
if statusOK
'remoteCtl.manualCalibrate()
debug("R/C Running...")
remoteControlMotor()
else
debug("EEEE: SBUS rcvr not started?!")
' turn off our SBUS drivers
remoteCtl.stop()
' turn off our motor drivers
wheels.stop()
else
debug("* ERROR user configuration NOT valid!")
debug("* DONE")
PRI connectMotorToHDMI() | nGroups, pGroupTitles, pGroupNames, pGroupVarCts, pGroupVars
' connect our two motors to the HDMI display mech
if bUseHDMI
nGroups, pGroupTitles, pGroupNames, pGroupVarCts, pGroupVars := wheels.getLeftDebugData()
debug("* Received Lt: ", udec(nGroups), uhex_long(pGroupTitles), uhex_long(pGroupNames), uhex_long(pGroupVarCts), uhex_long(pGroupVars))
tvDebug.registerDisplay(nGroups, pGroupTitles, pGroupNames, pGroupVarCts, pGroupVars)
'{ -- in-active until this can work! --
nGroups, pGroupTitles, pGroupNames, pGroupVarCts, pGroupVars := wheels.getRightDebugData()
debug("* Received Rt: ", udec(nGroups), uhex_long(pGroupTitles), uhex_long(pGroupNames), uhex_long(pGroupVarCts), uhex_long(pGroupVars))
tvDebug.registerDisplay(nGroups, pGroupTitles, pGroupNames, pGroupVarCts, pGroupVars)
'}
'{ -- in-active until this can work! --
nGroups, pGroupTitles, pGroupNames, pGroupVarCts, pGroupVars := wheels.getDebugData()
debug("* Received Steer: ", udec(nGroups), uhex_long(pGroupTitles), uhex_long(pGroupNames), uhex_long(pGroupVarCts), uhex_long(pGroupVars))
tvDebug.registerDisplay(nGroups, pGroupTitles, pGroupNames, pGroupVarCts, pGroupVars)
'}
PRI waitUntilMotorReady()
if wheels.isReady() == false
debug("* wait motors ready...")
repeat
if wheels.isReady()
quit
else
waitms(2)
debug("* Motors ready, let's drive!")
PRI waitUntilMotorDone()
if wheels.isStarting() == false
debug("* wait until motors start...")
repeat
if wheels.isStarting()
quit
else
waitms(2)
if wheels.isStopped() == false
debug("* wait until motors finish...")
repeat
if wheels.isStopped()
quit
else
waitms(2)
debug("* Motors stopped!")
CON
VALUE_NOT_SET = -2
VAR
long priorSpeed
long priorDirection
long rcSpeed
long rcDirection
long nLtAmps
long nLtWatts
long nRtAmps
long nRtWatts
long bLastShowState
long bLastEmerCutoff
long bLastIgnoreJoyStks
long bLastShowDriveStates
long nAccelerationRate
long nDoingOneRotation
PUB remoteControlMotor() | bIgnoreJoySticks, bDoneTesting, bShowState, loopCt, bShowDebugStatus, bEmerCutoff, bShowDriveStates, accrate, bOneRotation
'' Listen to FlySky and control motor, get status based on Switch/Joystick inputs
waitms(500) ' wait for 1/2 sec for backend to catch up
'arm.gripClosed()
debug("------")
debug("- Lt Joy Hz - direction")
debug("- Rt Joy Vt - speed")
debug("------")
debug("* swA DN - enable joystick servo control")
debug("* swB Toggle - show state")
'debug("* swC UP - ---")
'debug("* swC MID - ---")
debug("* swC DN - end control")
debug("* swD DN - emer cutoff")
debug("* swE DN - 1 rotation")
debug("* VRA - acceleration")
debug("------")
bLastShowState := VALUE_NOT_SET ' value can't happen
bLastIgnoreJoyStks := VALUE_NOT_SET ' value can't happen
bLastEmerCutoff := VALUE_NOT_SET ' value can't happen
bLastShowDriveStates := VALUE_NOT_SET ' value can't happen
loopCt := 0
repeat
'debug("* ", udec_long(loopCt))
bShowDebugStatus := FALSE 'loopCt < 2 ? TRUE : FALSE
'remoteCtl.showDebug(bShowDebugStatus)
' SwA Ignore JoySticks
'debug("-- -- SW -- --")
bIgnoreJoySticks := remoteCtl.swIsOn(remoteCtl.CTL_SW_A)
bShowState := remoteCtl.swIsOff(remoteCtl.CTL_SW_B)
' SwC done, end loop!
bDoneTesting := remoteCtl.swIsOff(remoteCtl.CTL_SW_C)
bShowDriveStates := remoteCtl.swIsMiddle(remoteCtl.CTL_SW_C)
' SwD down = Emergency Cutoff
remoteCtl.showDebug(bShowDebugStatus)
bEmerCutoff := remoteCtl.swIsOff(remoteCtl.CTL_SW_D)
remoteCtl.showDebug(FALSE)
bOneRotation := remoteCtl.swIsOn(remoteCtl.CH_11)
accrate := remoteCtl.readchannel(remoteCtl.CTL_VRA)/10
if bLastShowDriveStates <> bShowDriveStates
debug("- sho ", sdec_long_(bShowDriveStates))
if bShowDriveStates
wheels.showDriveStates()
bLastShowDriveStates := bShowDriveStates
if bShowState <> bLastShowState
'showServoPositions()
if bShowState
nLtAmps, nLtWatts, nRtAmps, nRtWatts := wheels.getCurrent()
debug(" ltA=", sdec_long_(nLtAmps), ", rtA=", sdec_long_(nRtAmps))
bLastShowState := bShowState
if bEmerCutoff <> bLastEmerCutoff
'debug(" NEW E VALUE")
if bEmerCutoff
debug("------- Motor E-OFF")
wheels.emergencyCutoff()
else
wheels.clearEmergency()
if not bIgnoreJoySticks
debug(" Motor Enabled")
else
debug(" Motor Disabled")
bLastEmerCutoff := bEmerCutoff
if not bShowDebugStatus and bLastIgnoreJoyStks <> bIgnoreJoySticks
if bIgnoreJoySticks
debug(" Motor CTL OFF")
else
debug(" Motor CTL enabled")
bLastIgnoreJoyStks := bIgnoreJoySticks
if accrate <> 0 and nAccelerationRate <> accrate
nAccelerationRate := accrate
debug(" Setting Motor Acceleration:", sdec(nAccelerationRate))
wheels.setAcceleration(nAccelerationRate)
if not bEmerCutoff
rcSpeed, rcDirection := updPosnBothJoy()
if not bIgnoreJoySticks
rcDirection := 0 - rcDirection ' invert this to apply to our motors
if priorDirection <> rcDirection or priorSpeed <> rcSpeed
debug("- JOY ", sdec_long(rcSpeed), sdec_long(rcDirection))
wheels.driveDirection(rcSpeed, rcDirection)
priorDirection := rcDirection
priorSpeed := rcSpeed
elseif priorSpeed <> 0 and rcSpeed == 0
' if we were running when motors control stopped then allow a stop when it happens
debug("- JOY (last) ", sdec_long(rcSpeed), sdec_long(rcDirection))
wheels.driveDirection(rcSpeed, rcDirection)
priorDirection := rcDirection
priorSpeed := rcSpeed
elseif bOneRotation == false and nDoingOneRotation == false ' no emergency cutoff and no joystick before accept 1 rotation
nDoingOneRotation := true
doOneRotation()
elseif bOneRotation == true and nDoingOneRotation == true ' switch must be reset before allowed again
nDoingOneRotation := false
if bDoneTesting
debug("--> quit loop")
quit
waitms(250) ' wait 1/4 second, before next loop
loopCt++
' done, stop our motors
wheels.stop()
PRI doOneRotation() | ltdegree, rtdegree
ltdegree, rtdegree := wheels.getRotationCount(wheels.DRU_DEGREES) ' get current wheel rotation
wheels.driveDirection(10, 0) ' drive forward slowly
debug(" Onrotation Driving:", sdec(ltdegree), " ", sdec(rtdegree))
wheels.stopAfterRotation(ltdegree+360, wheels.DRU_DEGREES) ' stop after 360degree wheel rotation
ltdegree, rtdegree := wheels.getRotationCount(wheels.DRU_DEGREES) ' get current wheel rotation
debug(" Onrotation Stopped:", sdec(ltdegree), " ", sdec(rtdegree))
waitms(1000)
ltdegree, rtdegree := wheels.getRotationCount(wheels.DRU_DEGREES) ' get current wheel rotation
debug(" Onrotation Check:", sdec(ltdegree), " ", sdec(rtdegree))
PRI updPosnBothJoy(): speed, direction | rawSpeed, rawDirection, rngMin, rngMax
' route Rt Joystick Vt (spring center) to FWD/REV (speed)
'debug("-- JOY -- JOY --")
rawSpeed := remoteCtl.readChannel(remoteCtl.CTL_RT_JOY_VT)
rngMin, rngMax := remoteCtl.chanMinMax(remoteCtl.CTL_RT_JOY_VT)
speed := map(rawSpeed, rngMin, rngMax, -100, +100)
' route Lt Joystick Hz (spring center) to direction
rawDirection := remoteCtl.readChannel(remoteCtl.CTL_LT_JOY_HZ)
rngMin, rngMax := remoteCtl.chanMinMax(remoteCtl.CTL_LT_JOY_HZ)
direction := map(rawDirection, rngMin, rngMax, -100, +100)
PRI map(inValue, inMin, inMax, outMin, outMax) : outValue
{
REF: https://www.arduino.cc/reference/en/language/functions/math/map
Re-maps a number from one range to another. That is, a value of fromLow would get mapped to toLow,
a value of fromHigh to toHigh, values in-between to values in-between, etc.
Does not constrain values to within the range, because out-of-range values are sometimes intended and
useful. The constrain() function may be used either before or after this function, if limits to the ranges are desired.
Note that the "lower bounds" of either range may be larger or smaller than the "upper bounds" so the
map() function may be used to reverse a range of numbers, for example
y = map(x, 1, 50, 50, 1);
The function also handles negative numbers well, so that this example
y = map(x, 1, 50, 50, -100);
is also valid and works well.
The map() function uses integer math so will not generate fractions, when the math might indicate that
it should do so. Fractional remainders are truncated, and are not rounded or averaged.
}
if (inValue <= inMin)
outValue := outMin
elseif (inValue >= inMax)
outValue := outMax
else
outValue := (inValue - inMin) * (outMax - outMin) / (inMax - inMin) + outMin
CON { license }
{{
-------------------------------------------------------------------------------------------------
MIT License
Copyright (c) 2023 Iron Sheep Productions, LLC
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
=================================================================================================
}}