forked from KurtE/Phantom_Phoenix
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathPS2_Controller.cpp
483 lines (420 loc) · 15.9 KB
/
PS2_Controller.cpp
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
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
//====================================================================
//Project Lynxmotion Phoenix
//Description: Phoenix, control file.
//The control input subroutine for the phoenix software is placed in this file.
//Can be used with V2.0 and above
//Configuration version: V1.0
//Date: 25-10-2009
//Programmer: Jeroen Janssen (aka Xan)
// Kurt Eckhardt (aka KurtE) - converted to c ported to Arduino...
//
//Hardware setup: PS2 version
//
//NEW IN V1.0
//- First Release
//
//Walk method 1:
//- Left StickWalk/Strafe
//- Right StickRotate
//
//Walk method 2:
//- Left StickDisable
//- Right StickWalk/Rotate
//
//
//PS2 CONTROLS:
//[Common Controls]
//- StartTurn on/off the bot
//- L1Toggle Shift mode
//- L2Toggle Rotate mode
//- CircleToggle Single leg mode
// - Square Toggle Balance mode
//- TriangleMove body to 35 mm from the ground (walk pos)
//and back to the ground
//- D-Pad upBody up 10 mm
//- D-Pad downBody down 10 mm
//- D-Pad leftdecrease speed with 50mS
//- D-Pad rightincrease speed with 50mS
//
//[Walk Controls]
//- selectSwitch gaits
//- Left Stick(Walk mode 1) Walk/Strafe
// (Walk mode 2) Disable
//- Right Stick(Walk mode 1) Rotate,
//(Walk mode 2) Walk/Rotate
//- R1Toggle Double gait travel speed
//- R2Toggle Double gait travel length
//
//[Shift Controls]
//- Left StickShift body X/Z
//- Right StickShift body Y and rotate body Y
//
//[Rotate Controls]
//- Left StickRotate body X/Z
//- Right StickRotate body Y
//
//[Single leg Controls]
//- selectSwitch legs
//- Left StickMove Leg X/Z (relative)
//- Right StickMove Leg Y (absolute)
//- R2Hold/release leg position
//
//[GP Player Controls]
//- selectSwitch Sequences
//- R2Start Sequence
//
//====================================================================
// [Include files]
#if ARDUINO>99
#include <Arduino.h> // Arduino 1.0
#else
#include <Wprogram.h> // Arduino 0022
#endif
#include "Hex_Globals.h"
#ifdef USEPS2
#include <PS2X_lib.h>
//[CONSTANTS]
#define WALKMODE 0
#define TRANSLATEMODE 1
#define ROTATEMODE 2
#define SINGLELEGMODE 3
#define GPPLAYERMODE 4
#define cTravelDeadZone 4 //The deadzone for the analog input from the remote
#define MAXPS2ERRORCNT 5 // How many times through the loop will we go before shutting off robot?
#ifndef MAX_BODY_Y
#define MAX_BODY_Y 100
#endif
//=============================================================================
// Global - Local to this file only...
//=============================================================================
PS2X ps2x; // create PS2 Controller Class
// Define an instance of the Input Controller...
InputController g_InputController; // Our Input controller
static short g_BodyYOffset;
static short g_sPS2ErrorCnt;
static short g_BodyYShift;
static byte ControlMode;
static bool DoubleHeightOn;
static bool DoubleTravelOn;
static bool WalkMethod;
byte GPSeq; //Number of the sequence
short g_sGPSMController; // What GPSM value have we calculated. 0xff - Not used yet
// some external or forward function references.
extern void PS2TurnRobotOff(void);
//==============================================================================
// This is The function that is called by the Main program to initialize
//the input controller, which in this case is the PS2 controller
//process any commands.
//==============================================================================
// If both PS2 and XBee are defined then we will become secondary to the xbee
void InputController::Init(void)
{
int error;
//error = ps2x.config_gamepad(57, 55, 56, 54); // Setup gamepad (clock, command, attention, data) pins
error = ps2x.config_gamepad(PS2_CLK, PS2_CMD, PS2_SEL, PS2_DAT); // Setup gamepad (clock, command, attention, data) pins
g_BodyYOffset = 0;
g_BodyYShift = 0;
g_sPS2ErrorCnt = 0; // error count
ControlMode = WALKMODE;
DoubleHeightOn = false;
DoubleTravelOn = false;
WalkMethod = false;
g_InControlState.SpeedControl = 100; // Sort of migrate stuff in from Devon.
}
//==============================================================================
// This function is called by the main code to tell us when it is about to
// do a lot of bit-bang outputs and it would like us to minimize any interrupts
// that we do while it is active...
//==============================================================================
void InputController::AllowControllerInterrupts(boolean fAllow)
{
// We don't need to do anything...
}
//==============================================================================
// This is The main code to input function to read inputs from the PS2 and then
//process any commands.
//==============================================================================
void InputController::ControlInput(void)
{
boolean fAdjustLegPositions = false;
// Then try to receive a packet of information from the PS2.
// Then try to receive a packet of information from the PS2.
ps2x.read_gamepad(); //read controller and set large motor to spin at 'vibrate' speed
// Wish the library had a valid way to verify that the read_gamepad succeeded... Will hack for now
if ((ps2x.Analog(1) & 0xf0) == 0x70) {
// In an analog mode so should be OK...
g_sPS2ErrorCnt = 0; // clear out error count...
if (ps2x.ButtonPressed(PSB_START)) {// OK lets try "0" button for Start.
if (g_InControlState.fHexOn) {
PS2TurnRobotOff();
}
else {
//Turn on
g_InControlState.fHexOn = 1;
fAdjustLegPositions = true;
}
}
if (g_InControlState.fHexOn) {
// [SWITCH MODES]
//Translate mode
if (ps2x.ButtonPressed(PSB_L1)) {// L1 Button Test
MSound( 1, 50, 2000);
if (ControlMode != TRANSLATEMODE )
ControlMode = TRANSLATEMODE;
else {
if (g_InControlState.SelectedLeg==255)
ControlMode = WALKMODE;
else
ControlMode = SINGLELEGMODE;
}
}
//Rotate mode
if (ps2x.ButtonPressed(PSB_L2)) { // L2 Button Test
MSound( 1, 50, 2000);
if (ControlMode != ROTATEMODE)
ControlMode = ROTATEMODE;
else {
if (g_InControlState.SelectedLeg == 255)
ControlMode = WALKMODE;
else
ControlMode = SINGLELEGMODE;
}
}
//Single leg mode fNO
if (ps2x.ButtonPressed(PSB_CIRCLE)) {// O - Circle Button Test
if (abs(g_InControlState.TravelLength.x)<cTravelDeadZone && abs(g_InControlState.TravelLength.z)<cTravelDeadZone
&& abs(g_InControlState.TravelLength.y*2)<cTravelDeadZone ) {
if (ControlMode != SINGLELEGMODE) {
ControlMode = SINGLELEGMODE;
if (g_InControlState.SelectedLeg == 255) //Select leg if none is selected
g_InControlState.SelectedLeg=cRF; //Startleg
}
else {
ControlMode = WALKMODE;
g_InControlState.SelectedLeg=255;
}
}
}
#ifdef OPT_GPPLAYER
// GP Player Mode X
if (ps2x.ButtonPressed(PSB_CROSS)) { // X - Cross Button Test
MSound(1, 50, 2000);
if (ControlMode != GPPLAYERMODE) {
ControlMode = GPPLAYERMODE;
GPSeq=0;
}
else
ControlMode = WALKMODE;
}
#endif // OPT_GPPLAYER
//[Common functions]
//Switch Balance mode on/off
if (ps2x.ButtonPressed(PSB_SQUARE)) { // Square Button Test
g_InControlState.BalanceMode = !g_InControlState.BalanceMode;
if (g_InControlState.BalanceMode) {
MSound(1, 250, 1500);
}
else {
MSound( 2, 100, 2000, 50, 4000);
}
}
//Stand up, sit down
if (ps2x.ButtonPressed(PSB_TRIANGLE)) { // Triangle - Button Test
if (g_BodyYOffset>0)
g_BodyYOffset = 0;
else
g_BodyYOffset = 35;
fAdjustLegPositions = true;
}
if (ps2x.ButtonPressed(PSB_PAD_UP)) {// D-Up - Button Test
g_BodyYOffset += 10;
// And see if the legs should adjust...
fAdjustLegPositions = true;
if (g_BodyYOffset > MAX_BODY_Y)
g_BodyYOffset = MAX_BODY_Y;
}
if (ps2x.ButtonPressed(PSB_PAD_DOWN) && g_BodyYOffset) {// D-Down - Button Test
if (g_BodyYOffset > 10)
g_BodyYOffset -= 10;
else
g_BodyYOffset = 0; // constrain don't go less than zero.
// And see if the legs should adjust...
fAdjustLegPositions = true;
}
if (ps2x.ButtonPressed(PSB_PAD_RIGHT)) { // D-Right - Button Test
if (g_InControlState.SpeedControl>0) {
g_InControlState.SpeedControl = g_InControlState.SpeedControl - 50;
MSound( 1, 50, 2000);
}
}
if (ps2x.ButtonPressed(PSB_PAD_LEFT)) { // D-Left - Button Test
if (g_InControlState.SpeedControl<2000 ) {
g_InControlState.SpeedControl = g_InControlState.SpeedControl + 50;
MSound( 1, 50, 2000);
}
}
//[Walk functions]
if (ControlMode == WALKMODE) {
//Switch gates
if (ps2x.ButtonPressed(PSB_SELECT) // Select Button Test
&& abs(g_InControlState.TravelLength.x)<cTravelDeadZone //No movement
&& abs(g_InControlState.TravelLength.z)<cTravelDeadZone
&& abs(g_InControlState.TravelLength.y*2)<cTravelDeadZone ) {
g_InControlState.GaitType = g_InControlState.GaitType+1; // Go to the next gait...
if (g_InControlState.GaitType<NUM_GAITS) { // Make sure we did not exceed number of gaits...
MSound( 1, 50, 2000);
}
else {
MSound(2, 50, 2000, 50, 2250);
g_InControlState.GaitType = 0;
}
GaitSelect();
}
//Double leg lift height
if (ps2x.ButtonPressed(PSB_R1)) { // R1 Button Test
MSound( 1, 50, 2000);
DoubleHeightOn = !DoubleHeightOn;
if (DoubleHeightOn)
g_InControlState.LegLiftHeight = 80;
else
g_InControlState.LegLiftHeight = 50;
}
//Double Travel Length
if (ps2x.ButtonPressed(PSB_R2)) {// R2 Button Test
MSound(1, 50, 2000);
DoubleTravelOn = !DoubleTravelOn;
}
// Switch between Walk method 1 && Walk method 2
if (ps2x.ButtonPressed(PSB_R3)) { // R3 Button Test
MSound(1, 50, 2000);
WalkMethod = !WalkMethod;
}
//Walking
if (WalkMethod) //(Walk Methode)
g_InControlState.TravelLength.z = (ps2x.Analog(PSS_RY)-128); //Right Stick Up/Down
else {
g_InControlState.TravelLength.x = -(ps2x.Analog(PSS_LX) - 128);
g_InControlState.TravelLength.z = (ps2x.Analog(PSS_LY) - 128);
}
if (!DoubleTravelOn) { //(Double travel length)
g_InControlState.TravelLength.x = g_InControlState.TravelLength.x/2;
g_InControlState.TravelLength.z = g_InControlState.TravelLength.z/2;
}
g_InControlState.TravelLength.y = -(ps2x.Analog(PSS_RX) - 128)/4; //Right Stick Left/Right
}
//[Translate functions]
g_BodyYShift = 0;
if (ControlMode == TRANSLATEMODE) {
g_InControlState.BodyPos.x = (ps2x.Analog(PSS_LX) - 128)/2;
g_InControlState.BodyPos.z = -(ps2x.Analog(PSS_LY) - 128)/3;
g_InControlState.BodyRot1.y = (ps2x.Analog(PSS_RX) - 128)*2;
g_BodyYShift = (-(ps2x.Analog(PSS_RY) - 128)/2);
}
//[Rotate functions]
if (ControlMode == ROTATEMODE) {
g_InControlState.BodyRot1.x = (ps2x.Analog(PSS_LY) - 128);
g_InControlState.BodyRot1.y = (ps2x.Analog(PSS_RX) - 128)*2;
g_InControlState.BodyRot1.z = (ps2x.Analog(PSS_LX) - 128);
g_BodyYShift = (-(ps2x.Analog(PSS_RY) - 128)/2);
}
//[Single leg functions]
if (ControlMode == SINGLELEGMODE) {
//Switch leg for single leg control
if (ps2x.ButtonPressed(PSB_SELECT)) { // Select Button Test
MSound(1, 50, 2000);
if (g_InControlState.SelectedLeg<5)
g_InControlState.SelectedLeg = g_InControlState.SelectedLeg+1;
else
g_InControlState.SelectedLeg=0;
}
g_InControlState.SLLeg.x= (ps2x.Analog(PSS_LX) - 128)/2; //Left Stick Right/Left
g_InControlState.SLLeg.y= (ps2x.Analog(PSS_RY) - 128)/10; //Right Stick Up/Down
g_InControlState.SLLeg.z = (ps2x.Analog(PSS_LY) - 128)/2; //Left Stick Up/Down
// Hold single leg in place
if (ps2x.ButtonPressed(PSB_R2)) { // R2 Button Test
MSound(1, 50, 2000);
g_InControlState.fSLHold = !g_InControlState.fSLHold;
}
}
#ifdef OPT_GPPLAYER
//[GPPlayer functions]
if (ControlMode == GPPLAYERMODE) {
// Lets try some speed control... Map all values if we have mapped some before
// or start mapping if we exceed some minimum delta from center
// Have to keep reminding myself that commander library already subtracted 128...
if (g_ServoDriver.FIsGPSeqActive() ) {
if ((g_sGPSMController != 32767)
|| (ps2x.Analog(PSS_RY) > (128+16)) || (ps2x.Analog(PSS_RY) < (128-16)))
{
// We are in speed modify mode...
short sNewGPSM = map(ps2x.Analog(PSS_RY), 0, 255, -200, 200);
if (sNewGPSM != g_sGPSMController) {
g_sGPSMController = sNewGPSM;
g_ServoDriver.GPSetSpeedMultiplyer(g_sGPSMController);
}
}
}
//Switch between sequences
if (ps2x.ButtonPressed(PSB_SELECT)) { // Select Button Test
if (!g_ServoDriver.FIsGPSeqActive() ) {
if (GPSeq < 5) { //Max sequence
MSound(1, 50, 1500);
GPSeq = GPSeq+1;
}
else {
MSound(2, 50, 2000, 50, 2250);
GPSeq=0;
}
}
}
//Start Sequence
if (ps2x.ButtonPressed(PSB_R2))// R2 Button Test
if (!g_ServoDriver.FIsGPSeqActive() ) {
g_ServoDriver.GPStartSeq(GPSeq);
g_sGPSMController = 32767; // Say that we are not in Speed modify mode yet... valid ranges are 50-200 (both postive and negative...
}
else {
g_ServoDriver.GPStartSeq(0xff); // tell the GP system to abort if possible...
MSound (2, 50, 2000, 50, 2000);
}
}
#endif // OPT_GPPLAYER
//Calculate walking time delay
g_InControlState.InputTimeDelay = 128 - max(max(abs(ps2x.Analog(PSS_LX) - 128), abs(ps2x.Analog(PSS_LY) - 128)), abs(ps2x.Analog(PSS_RX) - 128));
}
//Calculate g_InControlState.BodyPos.y
g_InControlState.BodyPos.y = min(max(g_BodyYOffset + g_BodyYShift, 0), MAX_BODY_Y);
if (fAdjustLegPositions)
AdjustLegPositionsToBodyHeight(); // Put main workings into main program file
}
else {
// We may have lost the PS2... See what we can do to recover...
if (g_sPS2ErrorCnt < MAXPS2ERRORCNT)
g_sPS2ErrorCnt++; // Increment the error count and if to many errors, turn off the robot.
else if (g_InControlState.fHexOn)
PS2TurnRobotOff();
ps2x.reconfig_gamepad();
}
}
//==============================================================================
// PS2TurnRobotOff - code used couple of places so save a little room...
//==============================================================================
void PS2TurnRobotOff(void)
{
//Turn off
g_InControlState.BodyPos.x = 0;
g_InControlState.BodyPos.y = 0;
g_InControlState.BodyPos.z = 0;
g_InControlState.BodyRot1.x = 0;
g_InControlState.BodyRot1.y = 0;
g_InControlState.BodyRot1.z = 0;
g_InControlState.TravelLength.x = 0;
g_InControlState.TravelLength.z = 0;
g_InControlState.TravelLength.y = 0;
g_BodyYOffset = 0;
g_BodyYShift = 0;
g_InControlState.SelectedLeg = 255;
g_InControlState.fHexOn = 0;
AdjustLegPositionsToBodyHeight(); // Put main workings into main program file
}
#endif //USEPS2