-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathrobot.py
1174 lines (866 loc) · 42.1 KB
/
robot.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
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
import brickpi
import random
import time
from DataStructures import CircularBuffer
from DataStructures import Particle
from DataStructures import SignatureContainer
from DataStructures import LocationSignature
import math
from DataStructures import Map
import copy
interface = None
class Robot:
# attributes - ideally different components (motors, ultrasonic sensor, etc)
motors = [0,1]
sonar_motor_port = [3,2]
touch_ports = [0,1]
sonar_port = 3
usSensorBuffer = CircularBuffer.CircularBuffer()
signatureContainer = SignatureContainer.SignatureContainer()
waypoint2Number = {}
noOfParticles = 100
particles_list = []
x = 84
y = 30
theta = 0
speed = 6.0
sonarStartingAngle = 0 #Used to reset sonar position to face forward
#constructor
def __init__(self):
global interface
interface = brickpi.Interface()
interface.initialize()
interface.motorEnable(self.motors[0])
interface.motorEnable(self.motors[1])
interface.motorEnable(self.sonar_motor_port[0])
interface.motorEnable(self.sonar_motor_port[1]) # not used
interface.sensorEnable(self.touch_ports[0], brickpi.SensorType.SENSOR_TOUCH)
interface.sensorEnable(self.touch_ports[1], brickpi.SensorType.SENSOR_TOUCH)
interface.sensorEnable(self.sonar_port, brickpi.SensorType.SENSOR_ULTRASONIC)
motorParams = interface.MotorAngleControllerParameters()
motorParams.maxRotationAcceleration = 6.0
motorParams.maxRotationSpeed = 12.0
motorParams.feedForwardGain = 255/20.0
motorParams.minPWM = 8.0
motorParams.pidParameters.minOutput = -255
motorParams.pidParameters.maxOutput = 255
#position ctrl: 517, 1000, 13
#velocity ctrl: 100, 0, 0
motorParams.pidParameters.k_p = 517
motorParams.pidParameters.k_i = 1000
motorParams.pidParameters.k_d = 13
interface.setMotorAngleControllerParameters(self.motors[0],motorParams)
interface.setMotorAngleControllerParameters(self.motors[1],motorParams)
interface.setMotorAngleControllerParameters(self.sonar_motor_port[0],motorParams)
interface.setMotorAngleControllerParameters(self.sonar_motor_port[1],motorParams) #not used
#calculate sonar starting angle
sonarStartingAngle = interface.getMotorAngles(self.sonar_motor_port)[0][0]
self.createParticlesList()
print("starting sonar angle = " + str(sonarStartingAngle))
#temp draw debug, remove after
#self.printParticles()
#time.sleep(0.5)
#self.updatePosition(160,0)
#self.updatePosition(0,90)
#self.updatePosition(34,0)
def setSpeed(self, newSpeed):
self.speed = newSpeed
def getDistance(self,x,y):
return math.sqrt(float((self.x-x)*(self.x-x)) + float((self.y-y)*(self.y-y)))
# movement functions
def moveForwards(self, distance=-1, usingMCL = True):
bumped = False
if distance<0:
self.setMotorRotationSpeed(self.speed, self.speed)
while True:
if self.checkSensors(self.touch_ports[0]) and not self.checkSensors(self.touch_ports[1]):
self.reverseForkRight(90)
# self.setMotorRotationSpeed(self.speed, self.speed)
bumped = True
return bumped
elif not self.checkSensors(self.touch_ports[0]) and self.checkSensors(self.touch_ports[1]):
self.reverseForkLeft(90)
#self.setMotorRotationSpeed(self.speed, self.speed)
bumped = True
return bumped
elif self.checkSensors(self.touch_ports[0]) and self.checkSensors(self.touch_ports[1]):
self.reverseForkLeft(90)
#self.setMotorRotationSpeed(self.speed, self.speed)
bumped = True
return bumped
else:
angle = self.distToAngle(distance)
startAngle = interface.getMotorAngles(self.motors)[0][0]
bumped = self.increaseMotorAngle(angle, angle)
if bumped:
motorAngles = interface.getMotorAngles(self.motors)[0][0]
angleDiff = float(motorAngles-startAngle)
distanceTravelled = (float(angleDiff)/float(angle)) * distance
else:
distanceTravelled = distance
self.updatePosition(distanceTravelled, 0, usingMCL)
return bumped
def moveBackwards(self, distance=-1, usingMCL = True):
if distance<0:
self.setMotorRotationSpeed(-self.speed, -self.speed)
while True:
# sensor checks here
time.sleep(1)
else:
angle = self.distToAngle(-distance)
self.increaseMotorAngle(angle, angle, False)
self.updatePosition(-distance, 0, usingMCL)
def rotateRight(self, rotAngle,usingMCL = True):
print("NOW ROTATING RIGHT")
angle = self.rotAngleToMotorAngle(rotAngle)
self.increaseMotorAngle(angle, -angle)
self.updatePosition(0,-rotAngle,usingMCL)
def rotateLeft(self, rotAngle,usingMCL = True):
print ("NOW ROTATING LEFT")
angle = self.rotAngleToMotorAngle(rotAngle)
self.increaseMotorAngle(-angle, angle)
self.updatePosition(0, rotAngle,usingMCL)
def reverseForkLeft(self,angle):
print("reversing back now...")
interface.setMotorPwm(self.motors[0],0)
interface.setMotorPwm(self.motors[1],0)
print("moving back now....")
self.moveBackwards(20)
self.rotateLeft(angle)
def reverseForkRight(self,angle):
interface.setMotorPwm(self.motors[0],0)
interface.setMotorPwm(self.motors[1],0)
self.moveBackwards(20)
self.rotateRight(angle)
def Left90deg(self):
self.rotateLeft(90)
def Right90deg(self):
self.rotateRight(90)
def moveSquare(self,distance):
for i in range(0,4):
self.moveForwards(distance)
self.Left90deg()
time.sleep(0.05)
def MoveForwardsWithSonar(self, safeDistance):
while True:
usReading = self.readUsSensor(self.usSensorBuffer) #returns the median of the circular buffer
#print "median=",usReading
error = usReading - safeDistance
k = float(error)/30.0 #k gain - adjust for different smoothness
if k > 1:
k = 1
if k < -1:
k = -1
#print "k=",k
self.setMotorRotationSpeed(k*self.speed, k*self.speed)
#works for following left wall
def followWallWithSonar(self, distance):
while True:
usReading = self.readUsSensor(self.usSensorBuffer)
error = usReading - distance
if error > 30:
error = 30
if error < -30:
error = -30
k = 0.1
speed_right = self.speed + ((k/2)*(error))
speed_left = self.speed - ((k/2)*(error))
self.setMotorRotationSpeed(speed_left, speed_right)
def moveSquare40Stop10(self):
for i in range(0,4):
for i in range(0,4):
self.moveForwards(10)
self.rotateLeft(90)
#-============================================================ conversion functions
def distToAngle(self, dist):
#41.5 - w/ wheels
#41 with bumper
angle = float(dist * 15.0)/40
return angle
def angleToDist(self, angle):
dist = float(angle * 40.0)/15
return dist
def rotAngleToMotorAngle(self, rotationAngle):
#4.55 - w/ wheels
#4.85 - w/ rear bumper
return float(rotationAngle * 4.85) / 90.0
#used as wrapper for setting different pid values
def setMotorRotationSpeed(self, speed1, speed2):
motorParams = interface.MotorAngleControllerParameters()
motorParams.maxRotationAcceleration = 4.0
motorParams.maxRotationSpeed = 12.0
motorParams.feedForwardGain = 255/20.0
motorParams.minPWM = 1.0
motorParams.pidParameters.minOutput = -255
motorParams.pidParameters.maxOutput = 255
motorParams.pidParameters.k_p = 100
motorParams.pidParameters.k_i = 0
motorParams.pidParameters.k_d = 0
interface.setMotorAngleControllerParameters(self.motors[0],motorParams)
interface.setMotorAngleControllerParameters(self.motors[1],motorParams)
interface.setMotorRotationSpeedReferences(self.motors, [speed1,speed2])
# Used for sonar motor
def setMotorSonarRotationSpeed(self, speed):
motorParams = interface.MotorAngleControllerParameters()
motorParams.maxRotationAcceleration = 4.0
motorParams.maxRotationSpeed = 12.0
motorParams.feedForwardGain = 255/20.0
motorParams.minPWM = 1.0
motorParams.pidParameters.minOutput = -255
motorParams.pidParameters.maxOutput = 255
motorParams.pidParameters.k_p = 100
motorParams.pidParameters.k_i = 0
motorParams.pidParameters.k_d = 0
interface.setMotorAngleControllerParameters(self.sonar_motor_port[0],motorParams)
interface.setMotorRotationSpeedReferences(self.sonar_motor_port, [speed, 0])
#wrapper for motor rotation
def increaseMotorAngle(self, angle1, angle2, checkSensors = True):
motorParams = interface.MotorAngleControllerParameters()
motorParams.maxRotationAcceleration = 6.0
motorParams.maxRotationSpeed = 12.0
motorParams.feedForwardGain = 255/20.0
motorParams.minPWM = 8.0
motorParams.pidParameters.minOutput = -255
motorParams.pidParameters.maxOutput = 255
#517 , 1000,13
motorParams.pidParameters.k_p = 517
motorParams.pidParameters.k_i = 1000
motorParams.pidParameters.k_d = 13
interface.setMotorAngleControllerParameters(self.motors[0],motorParams)
interface.setMotorAngleControllerParameters(self.motors[1],motorParams)
interface.increaseMotorAngleReferences(self.motors,[angle1,angle2])
while not interface.motorAngleReferencesReached(self.motors) :
if checkSensors == True and (self.checkSensors(self.touch_ports[0]) or self.checkSensors(self.touch_ports[1])):
bumped = True
interface.setMotorPwm(self.motors[0],0)
interface.setMotorPwm(self.motors[1],0)
return bumped
else:
motorAngles = interface.getMotorAngles(self.motors)
#position control for sonar
def increaseMotorSonarAngle(self, angle):
motorParams = interface.MotorAngleControllerParameters()
motorParams.maxRotationAcceleration = 4.0
motorParams.maxRotationSpeed = 12.0
motorParams.feedForwardGain = 255/20.0
motorParams.minPWM = 1.0
motorParams.pidParameters.minOutput = -255
motorParams.pidParameters.maxOutput = 255
motorParams.pidParameters.k_p = 100
motorParams.pidParameters.k_i = 0
motorParams.pidParameters.k_d = 0
interface.setMotorAngleControllerParameters(self.sonar_motor_port[0],motorParams)
interface.setMotorAngleControllerParameters(self.sonar_motor_port[1],motorParams)
interface.increaseMotorAngleReferences(self.sonar_motor_port,[angle,0])
time.sleep(1.5)
#Sensor Functions
def checkSensors(self, touch_port):
result=interface.getSensorValue(touch_port)
if result:
touched=result[0]
else:
touched=0
return touched
def readUsSensor(self, circularBuffer):
#first fill up the circular buffer if it isn't already
usReading = interface.getSensorValue(self.sonar_port)
return usReading[0]
#if usReading:
#print(usReading)
#else:
#print "Failed to get Sonar reading."
circularBuffer.add(usReading[0])
return circularBuffer.getMedian()
#Waypoint functions
def readWayPoints(self,filename):
f = open(filename)
input = f.read()
pointList = list(map(int,input.split()))
n = pointList[0]
self.x = pointList[1]
self.y = pointList[2]
pointList = pointList[3:]
pointList = list(zip(pointList[0:2*n:2],pointList[1:2*n:2]))
for a,b in pointList:
print ("next waypoint: " + str(a) + "," + str(b))
while self.getDistance(a,b) > 1.0:
self.navigateToWaypoint(a,b)
def navigateToWaypoint(self, x, y):
b = math.sqrt((self.x-x)*(self.x-x) + (self.y-y)*(self.y-y))
while b > 0:
new_x=x-self.x
new_y=y-self.y
rel_angle=math.degrees(math.atan2(float(new_y), float(new_x)))
theta=self.theta%360
newAngle=rel_angle-theta
if (newAngle>=-180) and (newAngle<0):
self.rotateRight(abs(newAngle))
elif (newAngle<180) and (newAngle>=0):
self.rotateLeft(newAngle)
elif (newAngle>=180) and (newAngle<360):
self.rotateRight(360-newAngle)
elif (newAngle<-180) and (newAngle>-360):
self.rotateLeft(360+newAngle)
#if b > 20:
# b = b-20
#self.moveForwards(20)
#else :
#self.moveForwards(b)
#b = 0
#LOOP NEW
if b > 20:
b = b-20
self.moveForwards(20)
else:
self.moveForwards(b)
b = 0
# Particle Functions
def createParticlesList(self):
for i in range(0,self.noOfParticles):
self.particles_list.append(Particle.Particle())
self.particles_list[i].x = 84
self.particles_list[i].y = 30
self.particles_list[i].theta = 0
self.particles_list[i].weight = 1.0/float(self.noOfParticles)
def updateParticlePositions(self, distance, angle):
for particle in self.particles_list:
if(distance!=0):
particle.updateDistanceRandom(distance)
if(angle!=0):
particle.updateAngleRandom(angle)
def printParticles(self, justList = False):
if justList == False:
drawScale = 3 # Used to scale the particle positions on the screen
origin = (10,250)
Map.map.draw(origin, drawScale)
#draw origin
oLen = 5
print "drawLine:" + str(((origin[0]-oLen)*drawScale,origin[1]*drawScale,
(origin[0]+oLen)*drawScale,origin[1]*drawScale))
print "drawLine:" + str((origin[0]*drawScale,(origin[1]-oLen)*drawScale,
origin[0]*drawScale,(origin[1]+oLen)*drawScale))
p = []
for particle in self.particles_list:
p.append(((origin[0]+particle.x)*drawScale,(origin[1]-particle.y)*drawScale,-particle.theta))
print "drawParticles:" + str(p)
p = []
for particle in self.particles_list:
p.append((particle.x,particle.y,particle.theta))
#print p
time.sleep(1)
def printParticleWeights(self):
for p in self.particles_list:
print(p.weight)
#Positioning Functions
def updatePosition(self, distance, angle, usingMCL = True):
self.updateParticlePositions(distance, angle)
if usingMCL == True:
self.updateWeights()
self.printParticles()
x_sum = 0
y_sum = 0
theta_sum = 0
for particle in self.particles_list:
x_sum += particle.x*particle.weight
y_sum += particle.y*particle.weight
theta_sum += particle.theta*particle.weight
self.x = x_sum
self.y = y_sum
self.theta = theta_sum
print("CURRENT ROBOT POS: " + str((x_sum, y_sum, theta_sum)))
def calculate_likelihood(self,x, y, theta, z):
m_list = []
if z == 255:
return -1
for wall in Map.map.walls:
#A = x1,y1; B = x2,y2
#m: lecture 5 slide 18
x1 = wall[0]
y1 = wall[1]
x2 = wall[2]
y2 = wall[3]
#print ("current wall:" + str(wall))
if ((y2 == y1 and (theta % 180 == 0)) or (x2 == x1 and (theta % 180 == 90))):
m = -1
else:
m = float( ((y2-y1)*(x1-x)) - ((x2 - x1)*(y1 - y)) ) / float( ((y2 - y1)*math.cos(math.radians(theta))) - ((x2 - x1)*math.sin(math.radians(theta))) )
m_list.append(m)
min_m = 9999
min_m_index = 0
for i in range(len(m_list)):
if (m_list[i] >= 0 and m_list[i] < min_m):
current_wall = Map.map.walls[i]
x1 = current_wall[0]
y1 = current_wall[1]
x2 = current_wall[2]
y2 = current_wall[3]
intersect_x = x + m_list[i]*math.cos(math.radians(theta))
intersect_y = y + m_list[i]*math.sin(math.radians(theta))
# check if intersection is within wall region
if (intersect_x >= min(x1, x2)) and (intersect_x <= max(x1, x2)):
if( (intersect_y >= min(y1, y2)) and (intersect_y <= max(y1, y2)) ):
min_m = m_list[i]
min_m_index = i
current_wall = Map.map.walls[min_m_index]
#print("current wall =",current_wall)
x1 = current_wall[0]
y1 = current_wall[1]
x2 = current_wall[2]
y2 = current_wall[3]
k = 100.0
sigma_s = 1
#p(z|m)
prob = k*math.exp((-(z-min_m)*(z-min_m))/(2*sigma_s*sigma_s))
angle_of_incidence = math.degrees(
math.acos(
(
(math.cos(math.radians(theta)) * (y1 - y2))
+ (math.sin(math.radians(theta))*(x2 - x1))
)/(
math.sqrt(
((y1 - y2)*(y1 - y2))
+ ((x2 - x1)*(x2 - x1))
)
)
)
)
if angle_of_incidence < 49:
return prob
else:
return -1
def updateWeights(self):
for i in range(15):
z = self.readUsSensor(self.usSensorBuffer)
error_count = 0
particles_list_copy = copy.deepcopy(self.particles_list)
for particle in self.particles_list:
prob = self.calculate_likelihood(particle.x,particle.y,particle.theta, z)
if prob == -1:
error_count += 1
else:
particle.weight = particle.weight * prob
if(error_count > self.noOfParticles/4):
print("Too many errors. Using old weights.")
self.particles_list = copy.deepcopy(particles_list_copy)
self.normaliseParticlesList()
self.resampleParticlesList()
def normaliseParticlesList(self):
weightSum = 0
for particle in self.particles_list:
weightSum += particle.weight
if weightSum != 0:
for particle in self.particles_list:
particle.weight = float(particle.weight) /float(weightSum )
else:
for particle in self.particles_list:
particle.weight = 1/float(self.noOfParticles)
def getCumulativeWeights(self):
cumulative_weights = []
sum = 0
for p in self.particles_list:
sum += p.weight
cumulative_weights.append(sum)
return cumulative_weights
def resampleParticlesList(self):
cumulative_weights = self.getCumulativeWeights()
new_weight = 1.0/float(self.noOfParticles)
resampled_particles_list = []
# fill the resampled list
while len(resampled_particles_list) < self.noOfParticles:
randomWeight = random.random()
# find intersectiopn with cumulative array
# and add to the resampled list
for i in range(len(cumulative_weights)):
if(randomWeight >= cumulative_weights[i-1] and randomWeight <= cumulative_weights[i]):
resampled_particles_list.append(Particle.Particle())
j=len(resampled_particles_list) - 1
resampled_particles_list[j].x = self.particles_list[i].x
resampled_particles_list[j].y = self.particles_list[i].y
resampled_particles_list[j].theta = self.particles_list[i].theta
resampled_particles_list[j].weight = new_weight
break
# reassign the no. of particles
self.particles_list = copy.deepcopy(resampled_particles_list)
#=========================Place recognition functions================================================
#Place Recognition Functions
#def characterize_location(ls):
def learnLocation(self):
ls = LocationSignature.LocationSignature(360)
self.characterize_location(ls)
free_index = self.signatureContainer.get_free_index()
if(free_index == -1):
print("no more spaces left for storing signature")
#else:
#self.signatureContainer.save(ls,free_index)
print("COMPLETED")
ls.draw(self.x+10, 250-self.y, self.theta)
self.printParticles()
sonar_motor_direction = -1
def characterize_location(self, ls):
time_calibration = 0.02
self.setMotorSonarRotationSpeed(1 * self.sonar_motor_direction)
#for i in range(360):
for i in range(len(ls.sig)):
# b = 1
z = self.readUsSensor(self.usSensorBuffer)
ls.sig[i] = z
time.sleep(time_calibration)
interface.setMotorPwm(self.sonar_motor_port[0], 0)
self.setMotorSonarRotationSpeed(0)
self.sonar_motor_direction = self.sonar_motor_direction * -1
time.sleep(0.5)
time_calibration2 = 0.007
self.setMotorSonarRotationSpeed(3 * self.sonar_motor_direction)
for i in range(len(ls.sig)):
# b = 1
time.sleep(time_calibration2)
interface.setMotorPwm(self.sonar_motor_port[0], 0)
self.setMotorSonarRotationSpeed(0)
self.sonar_motor_direction = self.sonar_motor_direction * -1
"""
angle = self.rotAngleToMotorAngle(100)
self.increaseMotorSonarAngle(angle, ls)
"""
"""
# At any random waypoint
# output - the way point location
def recognizeLocation(self):
# take a reading from the sonar to create a reference list
ls_ref = LocationSignature.LocationSignature(360)
self.characterize_location(ls_ref)
# read all files and convert to depth histogram
least_squared_error = 999999999
best_match_index = -1
#hardcoded foir now - chang later
for index in range(5):
ls2 = self.signatureContainer.read(index)
# read function may return empty list
if(ls2 != [] ):
error = ls_ref.squared_histogram_error(ls2)
if(error < least_squared_error):
least_squared_error = error
best_match_index = index
print("leats error=",least_squared_error)
print("best_match_index = ",best_match_index)
# after loop is finished , we will get the best index.
#now use the index to get best match sonar reading
best_match_sonar = self.signatureContainer.read(index)
# A successful output will be the location of the waypoint.
waypointNumber = self.waypoint2Number[best_match_index]
print("The Recognized waypoint is =",waypointNumber )
"""
# ===============================SideWall Algorithm==========================
# Start Reading Here
# As of now this function only deals with Area C
# outermost function
def findObstacles(self):
print("Findgin obstacle...")
hitCount = 0
#============== Area C =========================
# preparation for area C
self.navigateToWaypoint(65,30)
#vrticla distance to wall y = 168 ,we move 15 less than that
distance = (168-15) - self.y
self.rotateRight(90)
#self.navigateToWaypoint(self.x,self.y+1)
#rotate sonar to face left
self.rotateSonar(-90)
objectFound = self.moveForwardsWithScanning(distance)
# either bumped into it while scanning or found it and then bumped into it.
if(objectFound == True):
print("incrementing hitCount....")
hitCount += 1
print("hit count = ",hitCount)
# Imp - need to decide what to do in this case. Not so obvious
# Best strategy is to have a specific case for each Area A,B and C
else:
print("No object found in the side scan!")
#navigateToWaypoint(a,b)
#===================================================
#== Area B #=====
# preparation for area B
# Need to be careful with bumping into wall c in MCL map
# 126 is the vertical location of point C in MCL map
if(self.y > 126 ):
self.navigateToWaypoint(self.x,30)
self.navigateToWaypoint(100,94)
else:
self.navigateToWaypoint(100,94)
print "waypoint B reached"
#while abs(self.theta - 90) > 2:
#self.rotateLeft(90-self.theta)
self.navigateToWaypoint(self.x,self.y+5)
print "rotation adjustment complete"
#vertical distance to wall d on mcl map
distance = (210-15) - self.y
#rotate sonar to face right
self.rotateSonar(90)
print "sonar in position"
objectFound = self.moveForwardsWithScanning(distance)
# either bumped into it while scanning or found it and then bumped into it.
if(objectFound == True):
print("incrementing hitCount....")
hitCount += 1
print("hit count = ",hitCount)
# Imp - need to decide what to do in this case. Not so obvious
# Best strategy is to have a specific case for each Area A,B and C
else:
print("No object found in the side scan!")
#navigateToWaypoint(a,b)
#============== Area A =========================
# preparation for area A
self.navigateToWaypoint(100,65)
self.navigateToWaypoint(100,55)
print("ROBOT Y IS AT ( shoudl be 55 )= ",self.y)
#self.navigateToWaypoint(100,15)
#shortcut to turn it straight , facing towards wall d
# (instead of finding orientation of robot to turn it straight)
#self.navigateToWaypoint(self.x,65)
self.navigateToWaypoint(self.x+3,self.y)
#vrticla distance to wall g = 84 ,we move 10 less than that
distance = (210-15) - self.x
#rotate sonar right
self.rotateSonar(90)
objectFound = self.moveForwardsWithScanning(distance)
# either bumped into it while scanning or found it and then bumped into it.
if(objectFound == True):
print("incrementing hitCount....")
hitCount += 1
print("hit count = ",hitCount)
# Imp - need to decide what to do in this case. Not so obvious
# Best strategy is to have a specific case for each Area A,B and C
else:
print("No object found in the side scan!")
#navigateToWaypoint(a,b)
#===================================================
if(hitCount == 3):
self.navigateToWaypoint(84,30)
print("Challeneg Completed")
#else:
#self.findObstacles()
def moveForwardsWithScanning(self, distance):
#returns true if hit bottle,
#returns result of Bump
#returns false if reached end
#Need this to calculate the fraction of distance
angle = self.distToAngle(distance)
motorParams = interface.MotorAngleControllerParameters()
motorParams.maxRotationAcceleration = 6.0
motorParams.maxRotationSpeed = 12.0
motorParams.feedForwardGain = 255/20.0
motorParams.minPWM = 8.0
motorParams.pidParameters.minOutput = -255
motorParams.pidParameters.maxOutput = 255
#position ctrl: 517, 1000, 13
#velocity ctrl: 100, 0, 0
motorParams.pidParameters.k_p = 517
motorParams.pidParameters.k_i = 1000
motorParams.pidParameters.k_d = 13
#set motor params
interface.setMotorAngleControllerParameters(self.motors[0],motorParams)
interface.setMotorAngleControllerParameters(self.motors[1],motorParams)
#print("ANGLE=",angle)
interface.increaseMotorAngleReferences(self.motors,[angle,angle])
startAngle = interface.getMotorAngles(self.motors)[0][0]
medianBuffer = CircularBuffer.CircularBuffer(20)
#set flags for the beginning and end of the bottle
angle_beginning = -1; #start of bottle
angle_end = -1; #end of bottle
bottle_start = False
bottle_end = False
y_begin = 0
y_end = 0
y_mid = 0
#Before setting off, take five values of the sonar to the wall to get a good median
for i in range(20):
medianBuffer.add([self.readUsSensor(self.usSensorBuffer), self.y])
wallDistance = self.readUsSensor(self.usSensorBuffer)
while not interface.motorAngleReferencesReached(self.motors) :
#print("moving forwards with scanning ...")
#bumped into the obstacle accidentally while moving straight.
if self.checkSensors(self.touch_ports[0]) or self.checkSensors(self.touch_ports[1]):
motorAngles = interface.getMotorAngles(self.motors)[0][0]
angleDiff = float(motorAngles-startAngle)
# calculate the fraction of the total distance that we travelled.
# Used for updating MCL after rotating sonarS
distanceTravelled = (float(angleDiff)/float(angle)) * distance
#stop motors
interface.setMotorPwm(self.motors[0],0)
interface.setMotorPwm(self.motors[1],0)
# need to rotate sonar to point forward for MCl to work
currentSonarAngle = interface.getMotorAngles(self.sonar_motor_port)[0][0]
if(currentSonarAngle > self.sonarStartingAngle):
self.rotateSonar(-90)
else:
self.rotateSonar(90)
# orientation of robot will not have changed since we moved straight only.
self.updatePosition(distanceTravelled, 0, False)
self.moveBackwards(15, False)
return True #hit bottle
else: #check sonar
bumped = False
currentAngle = interface.getMotorAngles(self.motors)[0][0]
usReading = self.readUsSensor(self.usSensorBuffer)
medianBuffer.add([usReading, currentAngle])
#calculate gradient
#print(medianBuffer.circularBuffer)
#wall x- bottle x distance
gradient = medianBuffer.circularBuffer[-1][0] - medianBuffer.circularBuffer[-2][0]
if gradient < -4 and angle_beginning == -1: #-ve gradient => entering bottle
print("entered bottle frame")
bottle_start = True
angle_beginning = medianBuffer.circularBuffer[-1][1]
elif gradient > 4 and angle_beginning != -1: #+ve gradient => exiting
#check if current y and beginning y distance is sensible (> 5 cm apart)
y_begin = self.angleToDist(angle_beginning)
if abs(y_begin - medianBuffer.circularBuffer[-1][1]) >= 5:
print("exited bottle frame")
angle_end = medianBuffer.circularBuffer[-1][1]
y_end = self.angleToDist(angle_end)
bottle_end = True
#if abs(usReading - wallDistance) > 8:
if(abs(gradient) <= 4 and bottle_start == True and bottle_end == True):
y_mid = float(y_begin + y_end)/2
self.moveBackwards(y_end - y_mid, False)
print ("y begin = "+ str(y_begin))
print ("y end = "+ str(y_end))
print ("y mid = "+ str(y_mid))
# find minimum of sonar readings to find obstacle centre
min_x = medianBuffer.circularBuffer[0][0]
for i in range(len(medianBuffer.circularBuffer)):
if min_x > medianBuffer.circularBuffer[i][0]:
min_x = medianBuffer.circularBuffer[i][0]
#obstacle_motor_angle = float(angle_beginning + angle_end)/2.0
obstacle_x = 0
obstacle_y = 0
print("sonar Found Obstacle!")
motorAngles = interface.getMotorAngles(self.motors)[0][0]
angleDiff = float(motorAngles-startAngle)
distanceTravelled = (float(angleDiff)/float(angle)) * distance
#stop motors
interface.setMotorPwm(self.motors[0],0)
interface.setMotorPwm(self.motors[1],0)
currentSonarAngle = interface.getMotorAngles(self.sonar_motor_port)[0][0]
# Major assumption - Increasing angles causes sonar to rotate left
# need to rotate sonar to point forward for MCL to work
if(currentSonarAngle < self.sonarStartingAngle ):
print("Rotating sonar right")
self.rotateSonar(90)
print("finished rotating")
#Again , like above , we have moved only vertically
self.updatePosition(distanceTravelled, 0)
obstacle_x = self.x - min_x
#print("OBSTACL_X = ",obstacle_x)
obstacle_y = self.y
else:
print("Rotating sonar left")
self.rotateSonar(-90)
#Again , like above , we have moved only vertically