-
Notifications
You must be signed in to change notification settings - Fork 0
/
Navigation.cs
1710 lines (1392 loc) · 63.3 KB
/
Navigation.cs
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
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using System.Threading;
using System.IO;
namespace DrRobot.JaguarControl
{
public class Navigation
{
#region Navigation Variables
public long[] LaserData = new long[DrRobot.JaguarControl.JaguarCtrl.DISDATALEN];
public double initialX=0, initialY=0, initialT=0;
public double x, y, t;
public double x_est, y_est, t_est;
public double x_des, y_des, t_des;
public double desiredX, desiredY, desiredT;
public double maxweight;
public double gyroAngle;
public double partAngle;
public bool newOdom = false;
public double lasersum =0, prevLaser =0;
public double currentEncoderPulseL, currentEncoderPulseR;
public double lastEncoderPulseL, lastEncoderPulseR;
public double wheelDistanceR, wheelDistanceL;
public double wheelDistRandR, wheelDistRandL;
public double tiltAngle, zoom;
public double currentAccel_x, currentAccel_y, currentAccel_z;
public double lastAccel_x, lastAccel_y, lastAccel_z;
public double currentGyro_x, currentGyro_y, currentGyro_z;
public double lastGyro_x, lastGyro_y, lastGyro_z;
public double last_v_x, last_v_y;
public double filteredAcc_x, filteredAcc_y;
public int robotType, controllerType;
enum ROBOT_TYPE { SIMULATED, REAL };
enum CONTROLLERTYPE { MANUALCONTROL, POINTTRACKER, EXPERIMENT };
public bool motionPlanRequired, displayParticles, displayNodes, displaySimRobot;
private JaguarCtrl jaguarControl;
private AxDRROBOTSentinelCONTROLLib.AxDDrRobotSentinel realJaguar;
private AxDDrRobotSentinel_Simulator simulatedJaguar;
private Thread controlThread;
private short motorSignalL, motorSignalR;
private short desiredRotRateR, desiredRotRateL;
public bool runThread = true;
public bool loggingOn;
StreamWriter logFile;
String streamPath_;
public bool logParticles, logLaserData, logParticleEst;
public int deltaT = 10;
private static int encoderMax = 32767;
public int pulsesPerRotation = 190;
public double wheelRadius = 0.089;
public double robotRadius = 0.242;//0.232
private double angleTravelled, distanceTravelled;
private double diffEncoderPulseL, diffEncoderPulseR;
private double maxVelocity = 0.25;
private double Kpho = 2;// w maxV = 0.3 ->1.5;
private double Kalpha = 30; //w maxV = 0.3 ->10.0;//2;//8
private double Kbeta = -0.5;// w maxV = 0.3 -> -1.0;//-0.5;//-0.5//-1.0;
const double alphaTrackingAccuracy = 0.10;
const double betaTrackingAccuracy = 0.1;
const double phoTrackingAccuracy = 0.10;
double time = 0;
DateTime startTime;
double currRotRateL, currRotRateR;
public short K_P = 15;//15;
public short K_I = 0;//0;
public short K_D = 3;//3;
public short frictionComp = 8750;//8750;
public double e_sum_R, e_sum_L;
public double u_R = 0;
public double u_L = 0;
public double e_R = 0;
public double e_L = 0;
public double e_L_last = 0;
public double e_R_last = 0;
public double rotRateL, rotRateR;
public double K_p, K_i, K_d, maxErr;
double encvelL, encvelR, odWheelVelL, odWheelVelR;
int countL, countR;
public double accCalib_x = 18;
public double accCalib_y = 4;
// PF Variables
public Map map;
public Particle[] particles;
public Particle[] propagatedParticles;
public Particle[] tempParticles;
public int numParticles = 1000;
public double K_wheelRandomness = 0.15;//0.25
public static Random random = new Random();
public bool newLaserData = false;
public double laserMaxRange = 6.0;
public double laserMinRange = 0.2;
public double[] laserAngles;
public double[] Weights;
private int laserCounter;
private int laserStepSize = 10;
public double[] distDiffs;
double angleTravelledGyro1, angleTravelledGyro;
double wheelstdR = 0.3;
double wheelstdL = 0.3;
double gyrostd = 0.03;
public List<Tuple<double, double>> trajPoints = new List<Tuple<double, double>>(); //trajectory to track
bool pointReached = false;
bool pathDefined = false;
public Node randExpansionNode;
public class Particle
{
public double x, y, t, w;
public Particle()
{
}
public Particle(Particle p)
{
x = p.x;
y = p.y;
t = p.t;
w = p.w;
}
}
// Motion Planner Variables
const int numXCells = 40;
const int numYCells = 40;
const int maxNumNodes = 5000;
const float minWorkspaceX = -40.0f;
const float maxWorkspaceX = 40.0f;
const float minWorkspaceY = -40.0f;
const float maxWorkspaceY = 40.0f;
// Motion Planner Variables
public double samplingCellSizeX, samplingCellSizeY;
public int numOccupiedCells;
public int[] occupiedCellsList;
public int[] numNodesInCell;
public Node[,] NodesInCells;
public Node[] trajList, nodeList;
public int trajSize, trajCurrentNode, numNodes;
public bool trackTrajPD = false;
public bool allGoalsRreached = false;
public double destX = 0;
public double destY = 0;//destinations to achieve for now
public bool followTrack = false;
public class Node
{
public double x, y;
public int lastNode;
public int nodeIndex;
public Node()
{
x = 0;
y = 0;
lastNode = 0;
nodeIndex = 0;
}
public Node(double _x, double _y, int _nodeIndex, int _lastNode)
{
x = _x;
y = _y;
nodeIndex = _nodeIndex;
lastNode = _lastNode;
}
}
public Boolean resetEverything = false;
//PWM Calibration variables
double interval = 0;
DateTime pt = DateTime.Now;
//short calibrate = 2048;
short calibrate = 4096;//CHANGE
short pwmModelR = 0;
short pwmModelL = 0;
double mR = -17.981;
double mL = 19.363;
double bR = 15781;
double bL = 17297;
#endregion
#region Navigation Setup
// Constructor for the Navigation class
public Navigation(JaguarCtrl jc)
{
// Initialize vars
jaguarControl = jc;
realJaguar = jc.realJaguar;
simulatedJaguar = jc.simulatedJaguar;
map = new Map();
particles = new Particle[numParticles];
propagatedParticles = new Particle[numParticles];
tempParticles = new Particle[4*numParticles];
// Create particles
for (int i = 0; i < numParticles; i++)
{
particles[i] = new Particle();
propagatedParticles[i] = new Particle();
tempParticles[i] = new Particle();
}
this.Initialize();
loggingOn = false;
logLaserData = false;
logParticles = true;
logParticleEst = true;
// Start Control Thread
controlThread = new Thread(new ThreadStart(runControlLoop));
controlThread.Start();
}
// All class variables are initialized here
// This is called every time the reset button is pressed
public void Initialize()
{
// Initialize state estimates
x = initialX;
y = initialY;
t = initialT;
// Initialize state estimates
if (jaguarControl.startMode == jaguarControl.KNOWN)
{
x_est = initialX;
y_est = initialY;
t_est = initialT;
}
else
{
x_est = 0;
y_est = 0;
t_est = 0;
}
// Set desired state
desiredX = initialX;
desiredY = initialY;
desiredT = initialT;
// Reset Localization Variables
wheelDistanceR = 0;
wheelDistanceL = 0;
// Zero actuator signals
motorSignalL = 0;
motorSignalR = 0;
// Set random start for particles
InitializeParticles();
gyroAngle = initialT;
angleTravelledGyro1 = 0;
// Set default to no motionPlanRequired
motionPlanRequired = true;
// Set visual display
tiltAngle = 25.0;
displayParticles = true;
displayNodes = true;
displaySimRobot = true;
laserAngles = new double[LaserData.Length];
distDiffs = new double[LaserData.Length];
for (int i = 0; i < LaserData.Length; i++)
laserAngles[i] = DrRobot.JaguarControl.JaguarCtrl.startAng + DrRobot.JaguarControl.JaguarCtrl.stepAng * i;
// MP variable setup
occupiedCellsList = new int[numXCells * numYCells];
numNodesInCell = new int[numXCells * numYCells];
NodesInCells = new Node[numXCells * numYCells, 500];
trajList = new Node[maxNumNodes];
nodeList = new Node[maxNumNodes];
numNodes = 0;
trajList[0] = new Node(0, 0, 0, 0);
trajSize = 0;
trajPoints.Clear();
allGoalsRreached = false;
destX = 0;
destY = 0;//destinations to achieve for now
pathDefined = false;
followTrack = false;
}
// This function is called from the dialogue window "Reset Button"
// click function. It resets all variables.
public void Reset()
{
simulatedJaguar.Reset();
GetFirstEncoderMeasurements();
CalibrateIMU();
Initialize();
}
#endregion
#region Main Loop
/************************ MAIN CONTROL LOOP ***********************/
// This is the main control function called from the control loop
// in the RoboticsLabDlg application. This is called at every time
// step.
// Students should choose what type of localization and control
// method to use.
public void runControlLoop()
{
// Wait
Thread.Sleep(500);
// Don't run until we have gotten our first encoder measurements to difference with
GetFirstEncoderMeasurements();
// Run infinite Control Loop
while (runThread)
{
// ****************** Additional Student Code: Start ************
// Students can select what type of localization and control
// functions to call here. For lab 1, we just call the function
// WallPositioning to have the robot maintain a constant distance
// to the wall (see lab manual).
// Update Sensor Readings
UpdateSensorMeasurements();
// Determine the change of robot position, orientation (lab 2)
MotionPrediction();
// Update the global state of the robot - x,y,t (lab 2)
LocalizeRealWithOdometry();
// Estimate the global state of the robot -x_est, y_est, t_est (lab 4)
LocalizeEstWithParticleFilter();
if (resetEverything)
{
Reset();
resetEverything = false;
}
// If using the point tracker, call the function
if (jaguarControl.controlMode == jaguarControl.AUTONOMOUS)
{
if (!pathDefined)
{
definePath();
}
if (trackTrajPD)
{
TrackTrajectory();
}
else
{
x_des = desiredX;
y_des = desiredY;
t_des = desiredT;
FlyToSetPoint();
}
// Actuate motors based actuateMotorL and actuateMotorR
if (jaguarControl.Simulating())
{
CalcSimulatedMotorSignals();
ActuateMotorsWithVelControl();
}
else
{
// Determine the desired PWM signals for desired wheel speeds
CalcMotorSignals();
ActuateMotorsWithPWMControl();
}
}
else
{
e_sum_L = 0;
e_sum_R = 0;
}
// ****************** Additional Student Code: End ************
// Log data
LogData();
// Sleep to approximate 20 Hz update rate
Thread.Sleep(deltaT); //not sure if this works anymore..... -wf
}
}
public void CalibrateIMU()
{
accCalib_x = 0;
accCalib_y = 0;
int numMeasurements = 100;
for (int i = 0; i < numMeasurements; i++)
{
accCalib_x += currentAccel_x;
accCalib_y += currentAccel_y;
Thread.Sleep(deltaT);
}
accCalib_x = accCalib_x / numMeasurements;
accCalib_y = accCalib_y / numMeasurements;
}
// Before starting the control loop, the code checks to see if
// the robot needs to get the first encoder measurements
public void GetFirstEncoderMeasurements()
{
if (!jaguarControl.Simulating())
{
// Get last encoder measurements
bool gotFirstEncoder = false;
int counter = 0;
while (!gotFirstEncoder && counter < 10)
{
try
{
currentEncoderPulseL = jaguarControl.realJaguar.GetEncoderPulse4();
currentEncoderPulseR = jaguarControl.realJaguar.GetEncoderPulse5();
lastEncoderPulseL = currentEncoderPulseL;
lastEncoderPulseR = currentEncoderPulseR;
gotFirstEncoder = true;
currentAccel_x = jaguarControl.getAccel_x();
currentAccel_y = jaguarControl.getAccel_y();
currentAccel_z = jaguarControl.getAccel_z();
lastAccel_x = currentAccel_x;
lastAccel_y = currentAccel_y;
lastAccel_z = currentAccel_z;
last_v_x = 0;
last_v_y = 0;
currentGyro_x = jaguarControl.getGyro_x();
currentGyro_y = jaguarControl.getGyro_y();
currentGyro_z = jaguarControl.getGyro_z();
lastGyro_x = currentGyro_x;
lastGyro_y = currentGyro_y;
lastGyro_z = currentGyro_z;
}
catch (Exception e) { }
counter++;
Thread.Sleep(100);
}
}
else
{
currentEncoderPulseL = 0;
currentEncoderPulseR = 0;
lastEncoderPulseL = 0;
lastEncoderPulseR = 0;
lastAccel_x = 0;
lastAccel_y = 0;
lastAccel_z = 0;
last_v_x = 0;
last_v_y = 0;
lastGyro_x = 0;
lastGyro_y = 0;
lastGyro_z = 0;
}
}
// At every iteration of the control loop, this function will make
// sure all the sensor measurements are up to date before
// makeing control decisions.
public void UpdateSensorMeasurements()
{
// For simulations, update the simulated measurements
if (jaguarControl.Simulating())
{
jaguarControl.simulatedJaguar.UpdateSensors(deltaT);
// Get most recenct encoder measurements
currentEncoderPulseL = simulatedJaguar.GetEncoderPulse4();
currentEncoderPulseR = simulatedJaguar.GetEncoderPulse5();
// Get most recent laser scanner measurements
laserCounter = laserCounter + deltaT;
newLaserData = false;
if (laserCounter >= 200)
{
for (int i = 0; i < LaserData.Length; i = i + laserStepSize)
{
//LaserData[i] = (long)(1000 * map.GetClosestWallDistance(x, y, t - initialT + laserAngles[i]));
LaserData[i] = (long)(1000 * map.GetClosestWallDistance(x, y, t - 1.57 + laserAngles[i]));
}
laserCounter = 0;
newLaserData = true;
}
}
else
{
// Get most recenct encoder measurements
try
{
// Update IMU Measurements
currentAccel_x = jaguarControl.getAccel_x();
currentAccel_y = jaguarControl.getAccel_y();
currentAccel_z = jaguarControl.getAccel_z();
currentGyro_x = jaguarControl.getGyro_x(); //check conversion of gyro signal
currentGyro_y = jaguarControl.getGyro_y();
currentGyro_z = jaguarControl.getGyro_z();
// Update Encoder Measurements
currentEncoderPulseL = jaguarControl.realJaguar.GetEncoderPulse4();
currentEncoderPulseR = jaguarControl.realJaguar.GetEncoderPulse5();
}
catch (Exception e)
{
}
}
}
// At every iteration of the control loop, this function calculates
// the PWM signal for corresponding desired wheel speeds
public void CalcSimulatedMotorSignals()
{
motorSignalL = (short)(desiredRotRateL);
motorSignalR = (short)(desiredRotRateR);
}
public void CalcMotorSignals()
{
short zeroOutput = 16383;
short maxPosOutput = 32767;
short calibrateInc = - 2* 1024;//2048;
short deadbandLimitL = 10000;
short deadbandLimitR = 10000;
//desiredRotRateL = (short)(maxVelocity * pulsesPerRotation / (Math.PI * 2));
//desiredRotRateL = (short)(maxVelocity * pulsesPerRotation / (Math.PI * 2));
//PWM model motor signal control based on calibration between PWM motor signal and encoder speed
double pwmL = 18.1224 * desiredRotRateL + 19085.111 - 3000; //5000 because calibration may or may not be correct
//double pwmL = 25 * desiredRotRateL + 19085.111; //I tried tweaking the slope here, since the robot was tending to the left. Need to recalibrate with 3 runs.
double pwmR = -18.224 * desiredRotRateR + 13855 + 3000;
//PID motor signal control
double K_p_L = 0.001; //0.02
double K_i_L = 0.7; //0.7
double K_d_L = 0.3;
double K_p_R = 0.001; //0.002
double K_i_R = 0.7; //0.7
double K_d_R = 0.3;//*/
/*double K_p_L = 0; //0.02
double K_i_L = 0; //0.5
double K_d_L = 0;
double K_p_R = 0; //0.002
double K_i_R = 0; //0.7
double K_d_R = 0;//*/
double maxErr = 8000 / deltaT;
/*
//PWM calibration test 2
TimeSpan ts = DateTime.Now - pt;
interval = ts.TotalSeconds;
motorSignalL = (short)(zeroOutput + calibrate);
motorSignalR = (short)(zeroOutput - calibrate);
if (interval >= 5)
{
calibrate += calibrateInc;
pt = DateTime.Now;
}//*/
currRotRateL = jaguarControl.leftFrontWheelMotor.encodeSpeed * jaguarControl.leftFrontWheelMotor.encoderDir;
currRotRateR = jaguarControl.rightFrontWheelMotor.encodeSpeed * jaguarControl.rightFrontWheelMotor.encoderDir;
e_L = desiredRotRateL - jaguarControl.leftFrontWheelMotor.encodeSpeed * jaguarControl.leftFrontWheelMotor.encoderDir;
e_R = desiredRotRateR - jaguarControl.rightFrontWheelMotor.encodeSpeed * jaguarControl.rightFrontWheelMotor.encoderDir;
e_sum_L = .9 * e_sum_L + e_L * deltaT;
e_sum_R = .9 * e_sum_R + e_R * deltaT;
e_sum_L = Math.Max(-maxErr, Math.Min(e_sum_L, maxErr));
e_sum_R = Math.Max(-maxErr, Math.Min(e_sum_R, maxErr));
u_L = ((K_p_L * e_L) + (K_i_L * e_sum_L) + (K_d_L * (e_L - e_L_last) / deltaT));
e_L_last = e_L;
u_R = ((K_p_R * e_R) + (K_i_R * e_sum_R) + (K_d_R * (e_R - e_R_last) / deltaT));
e_R_last = e_R;
// The following settings are used to help develop the controller in simulation.
// They will be replaced when the actual jaguar is used.
//motorSignalL = (short)(zeroOutput + desiredRotRateL * 100);// (zeroOutput + u_L);
//motorSignalR = (short)(zeroOutput - desiredRotRateR * 100);//(zeroOutput - u_R);
//motorSignalL = (short)(zeroOutput + u_L);
//motorSignalR = (short)(zeroOutput - u_R);
motorSignalL = (short)(pwmL + u_L);
motorSignalR = (short)(pwmR + u_R);
if (motorSignalL < (zeroOutput + deadbandLimitL))
if (motorSignalL > (zeroOutput - deadbandLimitL))
{
if (motorSignalL < (zeroOutput + 1000) && motorSignalL > (zeroOutput - 1000))
motorSignalL = zeroOutput;
else
motorSignalL = (short)((zeroOutput + Math.Sign(motorSignalL - zeroOutput) * deadbandLimitL));
}
if (motorSignalR < (zeroOutput + deadbandLimitR))
if(motorSignalR > (zeroOutput - deadbandLimitR))
{
if (motorSignalR < (zeroOutput + 1000) && motorSignalR > (zeroOutput - 1000))
motorSignalR = zeroOutput;
else
motorSignalR = (short)((zeroOutput + Math.Sign(motorSignalR - zeroOutput) * deadbandLimitR));
}//*/
//
motorSignalL = (short)Math.Min(maxPosOutput, Math.Max(0, (int)motorSignalL));
motorSignalR = (short)Math.Min(maxPosOutput, Math.Max(0, (int)motorSignalR));
}
// At every iteration of the control loop, this function sends
// the width of a pulse for PWM control to the robot motors
public void ActuateMotorsWithPWMControl()
{
if (jaguarControl.Simulating())
simulatedJaguar.DcMotorPwmNonTimeCtrAll(0, 0, 0, motorSignalL, motorSignalR, 0);
else
{
jaguarControl.realJaguar.DcMotorPwmNonTimeCtrAll(0, 0, 0, motorSignalL, motorSignalR, 0);
}
}
// At every iteration of the control loop, this function sends
// desired wheel velocities (in pulses / second) to the robot motors
public void ActuateMotorsWithVelControl()
{
if (jaguarControl.Simulating())
simulatedJaguar.DcMotorVelocityNonTimeCtrAll(0, 0, 0, motorSignalL, (short)(-motorSignalR), 0);
else
jaguarControl.realJaguar.DcMotorVelocityNonTimeCtrAll(0, 0, 0, motorSignalL, (short)(-motorSignalR), 0);
}
#endregion
#region Logging Functions
// This function is called from a dialogue window "Record" button
// It creates a new file and sets the logging On flag to true
// This function is called from a dialogue window "Record" button
// It creates a new file and sets the logging On flag to true
public void TurnLoggingOn()
{
//int fileCnt= 0;
//changed here
String date = DateTime.Now.Year.ToString() + "-" + DateTime.Now.Month.ToString() + "-" + DateTime.Now.Day.ToString() + "-" + DateTime.Now.Minute.ToString();
streamPath_ = "./E190Q_" + jaguarControl.fileName + ".csv";
ToString();
logFile = File.CreateText(streamPath_);
logFile.Close();
writeHeader();
startTime = DateTime.Now;
loggingOn = true;
}
// This function is called from a dialogue window "Record" button
// It closes the log file and sets the logging On flag to false
public void TurnLoggingOff()
{
if (logFile != null)
try
{
logFile.Close();
}
catch { }
loggingOn = false;
}
//This function is called when logging first starts to write the headers on the file being recorded
public void writeHeader()
{
String newData = "Time" + ", " + "x" + " ," + "y" + " , " + "t" + "," + "desL" + "," + "currL" + "," + "desR"+","+"currR";
newData += "," + "encodespeedL" + "," + "MotorSignalL" + "," + "encodespeedR" + "," + "MotorSignalR";
newData += "," + "Ang disp from gyro" + "," + "Tot Angle";
/*if (logParticleEst)
newData += "x_est" + "," + "y_est" + "," + "t_est" + ",";
if (logParticles)
{
for (int i = 0; i < numParticles; i++)
newData += "particles["+i+"x" + "," + "particles["+i+"].y" + "," + "particles["+i+"].t" + "," + "particles["+i+"].w" + ",";
}
if (logLaserData)
{
for (int i = 0; i < LaserData.Length; i = i + laserStepSize)
newData += "LaserData["+i+"]" + ",";
}
newData += "";*/
//newData += "," + "counter";
logFile = File.AppendText(streamPath_);
logFile.WriteLine(newData);
logFile.Close();
}
// This function is called at every iteration of the control loop
// IF the loggingOn flag is set to true, the function checks how long the
// logging has been running and records this time
private void LogData()
{
if (loggingOn)
{
//changed here
TimeSpan ts = DateTime.Now - startTime;
time = ts.TotalSeconds;
String newData = time.ToString() + ", " + x.ToString() + " ," + y.ToString() + " , " + t.ToString() + ","+ desiredRotRateL.ToString() + "," + currRotRateL.ToString() + "," + desiredRotRateR.ToString()+","+ currRotRateR.ToString() ;
newData += "," + jaguarControl.leftFrontWheelMotor.encodeSpeed.ToString() + "," + motorSignalL.ToString() + "," + jaguarControl.rightFrontWheelMotor.encodeSpeed.ToString() + "," + motorSignalR.ToString();
newData += "," + gyroAngle.ToString() + "," + angleTravelledGyro1.ToString();
/* if (logParticleEst)
newData += x_est + "," + y_est + "," + t_est + ",";
if (logParticles)
{
for (int i = 0; i < numParticles; i++)
newData += particles[i].x + "," + particles[i].y + "," + particles[i].t + "," + particles[i].w + ",";
}
if (logLaserData)
{
for (int i = 0; i < LaserData.Length; i = i + laserStepSize)
newData += LaserData[i] + ",";
}*/
//for (int i = 0; i < numParticles; i++)
// newData += distDiffs[i] + ",";
newData += "";
// newData += "," + countL + "," + countR; ;
logFile = File.AppendText(streamPath_);
logFile.WriteLine(newData);
logFile.Close();
}
}
#endregion
# region Control Functions
// This function is called at every iteration of the control loop
// It will drive the robot forward or backward to position the robot
// 1 meter from the wall.
private void WallPositioning()
{
// Here is the distance measurement for the central laser beam
double centralLaserRange = LaserData[113];
// ****************** Additional Student Code: Start ************
// Put code here to calculated motorSignalR and
// motorSignalL. Make sure the robot does not exceed
// maxVelocity!!!!!!!!!!!!
// Send Control signals, put negative on left wheel control
double error = centralLaserRange - 1;
int K = 20;
if (Math.Abs(error) < 0.05)
{
motorSignalR = 0; //desiredWheelSpeedR
motorSignalL = 0; //desiredWheelSpeedL
}
else
{
motorSignalL = (short)Math.Max(-100, Math.Min(100, K * error));
motorSignalR = (short)Math.Max(-100, Math.Min(100, K * error));
}
// ****************** Additional Student Code: End ************
}
// This function is called at every iteration of the control loop
// if used, this function can drive the robot to any desired
// robot state. It does not check for collisions
private void FlyToSetPoint()
{
// ****************** Additional Student Code: Start ************
// Put code here to calculate desiredRotRateR and
// desoredRotRateL. Make sure the robot does not exceed
// maxVelocity!!!!!!!!!!!!
desiredRotRateR = 0;
desiredRotRateL = 0;
double distThres = 0.4;
double thetaThres = Math.PI / 18;
maxVelocity = 0.2 * (2 * Math.PI) / wheelRadius;
//variables to be used in the function
double deltaX, deltaY, deltat;
double alpha, beta, rho;
double v, w;
double SR, SL, desiredVR, desiredVL;
double Kangle = 15;
//find difference from the desired point
deltaX = x_des - x_est;
deltaY = y_des - y_est;
deltat = t_des - t_est;
deltat = NormalizeAngles(deltat);//change x, y to x_est and y_est
//calculate rho and alpha
rho = Math.Sqrt(deltaX * deltaX + deltaY * deltaY);
alpha = -t + Math.Atan2(deltaY, deltaX);//changed t_est and t
alpha = NormalizeAngles(alpha);
v = Kpho * rho;
//change control law if the desired point is behind the robot
if (Math.Abs(alpha) > Math.PI / 2)
{
alpha = -t + Math.Atan2(-deltaY, -deltaX);
alpha = NormalizeAngles(alpha);
v = -Kpho * rho;
}
beta = deltat - alpha;
beta = NormalizeAngles(beta);
w = Kalpha * alpha + Kbeta * beta;
// stop if destination reached
if (rho < distThres)
{
v = 0;
w = Kangle * deltat;
//w = (-Kbeta * deltat) + (Math.Sign(deltat) * 2.0);
if (Math.Abs(deltat) < thetaThres)
{
w = 0;
}
}
//calculate desired velocities from v and w
SR = w / 2 + v / (2 * robotRadius);
SL = -w / 2 + v / (2 * robotRadius);
desiredVR = SR * 2.0 * robotRadius / wheelRadius;
desiredVL = SL * 2.0 * robotRadius / wheelRadius;
//don't exceed the maximum velocity
if (Math.Abs(desiredVR) > maxVelocity)
{
desiredVL *= maxVelocity / Math.Abs(desiredVR);
desiredVR = Math.Sign(desiredVR) * maxVelocity;
}
if (Math.Abs(desiredVL) > maxVelocity)
{
desiredVR *= maxVelocity / Math.Abs(desiredVL);
desiredVL = Math.Sign(desiredVL) * maxVelocity;
}
//set the rotation rate
desiredRotRateR = (short)(desiredVR * pulsesPerRotation / (Math.PI * 2));
desiredRotRateL = (short)(desiredVL * pulsesPerRotation / (Math.PI * 2));
//desiredRotRateL = 100;
//desiredRotRateR = 100;
// ****************** Additional Student Code: End ************
}
#endregion
#region Localization Functions
/************************ LOCALIZATION *********************** github*/
// This function will grab the most recent encoder measurements
// from either the simulator or the robot (whichever is activated)
// and use those measurements to predict the RELATIVE forward
// motion and rotation of the robot. These are referred to as
// distanceTravelled and angleTravelled respectively.
public void MotionPrediction()
{
// ****************** Additional Student Code: Start ************
// Put code here to calculated distanceTravelled and angleTravelled.
// You can set and use variables like diffEncoder1, currentEncoderPulse1,
// wheelDistanceL, wheelRadius, encoderResolution etc. These are defined
// in the Robot.h file.
diffEncoderPulseL = currentEncoderPulseL - lastEncoderPulseL;
diffEncoderPulseR = currentEncoderPulseR - lastEncoderPulseR;
if (diffEncoderPulseL < 0 && Math.Abs(diffEncoderPulseL) > 30000) // robot moving forwards and encoder rollover (LW CCW)
{
diffEncoderPulseL = (encoderMax % lastEncoderPulseL) + (currentEncoderPulseL + 1); //+1 bc pulse includes 0
}
if (diffEncoderPulseL > 30000) //robot moving backwards and encoder rollover (LW CW)
{
diffEncoderPulseL = (encoderMax % currentEncoderPulseL) + (lastEncoderPulseL + 1);
}
if (diffEncoderPulseR < 0 && Math.Abs(diffEncoderPulseR) > 30000) //robot moving backwards and encoder rollover (RW CCW)
{
diffEncoderPulseR = (encoderMax % lastEncoderPulseR) + (currentEncoderPulseR + 1);
}
if (diffEncoderPulseR > 30000) //robot moving forwards and encoder rollover (RW CW)
{
diffEncoderPulseR = (encoderMax % currentEncoderPulseR) + (lastEncoderPulseR + 1);
}
lastEncoderPulseL = currentEncoderPulseL;
lastEncoderPulseR = currentEncoderPulseR;
wheelDistanceL = (diffEncoderPulseL / pulsesPerRotation) * 2 * Math.PI * wheelRadius;
wheelDistanceR = -(diffEncoderPulseR / pulsesPerRotation) * 2 * Math.PI * wheelRadius;
distanceTravelled = (wheelDistanceL + wheelDistanceR) / 2; //deltaS from class
angleTravelled = (wheelDistanceR - wheelDistanceL) / (2 * robotRadius); //deltaTheta formula from class
if ((Math.Abs(distanceTravelled) == 0) && (Math.Abs(angleTravelled) == 0))
{
newOdom = false;
} //check for new odometry measurement i.e. robot has moved
else
{
newOdom = true;
}
gyroAngle = getGyroRadian(); //gyroangle travelled
// ****************** Additional Student Code: End ************
}
public double NormalizeAngles(double angle)
//normalizes given angle to be between pi and -pi
{
while (angle < -Math.PI)
{
angle = angle + 2 * Math.PI; //e.g. -7pi/4 = pi/4
}
while (angle > Math.PI)
{
angle = angle - 2 * Math.PI; //e.g. 7pi/4 = -pi/4
}