-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathros_ctrl.py~
executable file
·5158 lines (3903 loc) · 161 KB
/
ros_ctrl.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
#!/usr/bin/env python
import roslib; roslib.load_manifest('navigation_irl')
import rospy
from std_msgs.msg import String
from nav_msgs.msg import Odometry
from geometry_msgs.msg import PoseStamped, PoseWithCovarianceStamped, Point, Quaternion
import tf
import patrol.model
from patrol.model import *
import mdp.agent
import sys
import Queue
import subprocess
import multiprocessing
import random
import cPickle as pickle
import os
import numpy
import operator
from patrol.time import *
import time
home = os.environ['HOME']
def get_home():
global home
return home
startat = 0
def get_time():
global startat
return rospy.get_time() - startat
# ros publications
pub = None
goal = None
state = "w"
# mdp Settings
startState = None
# mdp States
lastPatroller0State = None
lastPatroller1State = None
# class for holding the MDP and utils
mdpWrapper = None
# actual Map positions
cur_waypoint = [0,0]
lastPositionBelief = None
lastActualPosition = None
lastPatroller0Position1 = None
lastPatroller0Position2 = None
lastPatroller1Position1 = None
lastPatroller1Position2 = None
maxsightdistance = 6
patroller0GroundTruth = None
patroller1GroundTruth = None
mapToUse = None
patroller = None
obstime = 900
interactionLength = 1
patrollersuccessrate = None
usesimplefeatures = False
use_em = 0
patrollerOGMap = None
attackerOGMap = None
equilibriumKnown = False
global minGapBwDemos, patroller0LastSeenAt, patroller1LastSeenAt, \
BatchIRLflag, lastQ, min_IncIRL_InputLen, irlfinish_time, \
patrtraj_len, min_BatchIRL_InputLen, startat, glbltrajstarttime, \
startat_attpolicyI2RL, cum_learntime, \
desiredRecordingLen, useRecordedTraj, recordConvTraj, learned_mu_E, \
sessionNumber, learned_weights, num_Trajsofar, normedRelDiff, \
stopI2RLThresh, sessionStart, sessionFinish, lineFoundWeights, \
lineFeatureExpec, lineLastBeta, lineLastZS, lineLastZcount, lastQ, \
wt_data, print_once, useRecordedTraj, recordConvTraj, boydpolicy,\
learned_mu_E
#I2RL
BatchIRLflag=False
sessionNumber=1
num_Trajsofar=0
normedRelDiff=sys.maxint*1.0 # start with a high value to call update()
stopI2RLThresh=0.0095 #tried 0.0001, didn't go below 0.025 0.04
sessionStart=False
sessionFinish=False
lineFoundWeights=""
lineFeatureExpec=""
lineFeatureExpecfull=""
lineLastBeta=""
lineLastZS=""
lineLastZcount=""
lastQ="" #final likelihood value achieved
print_once=0
#flags for choosing to use recorded trajectories, and to execute only learning or full attack
useRecordedTraj = 0
recordConvTraj = 0
analyzeAttack = 0
boydpolicy = {}
#print("initialized global variables")
class FakeModel():
def T(self, state, action):
return {0 : 1}
def A(self):
return [0, ]
# a strategy that waits a random amount of time and then goes, ignores all percepts
class WrapperRandom():
def __init__(self, mapToUse, startPos, goalPos, goalPos2, reward, penalty, detectDistance):
global obstime, start_forGoTime, timeoutThresh
self.goTime = random.randint(start_forGoTime, 2*timeoutThresh) #obstime, obstime+600)
self.policy = None
print("The Go time is at: " + str(self.goTime))
self.predictTime = 30
self.map = mapToUse
self.observableStateLow = 0
self.observableStateHigh = 0
global attackerOGMap
p_fail = 0.05
## Create Model
self.goalStates = [self.getStateFor(goalPos), ]
self.goalState = self.goalStates[0]
model = patrol.model.AttackerModel(p_fail, attackerOGMap.theMap(), self.predictTime, self.goalStates[0])
model.gamma = 0.99
self.model = model
self.startState = self.getStateFor(startPos)
import threading
t = threading.Thread(target=self.solve)
self.thread = t
self.thread.start()
def solve(self):
global patroller0GroundTruth
global patroller1GroundTruth
while(patroller0GroundTruth is None or patroller1GroundTruth is None):
time.sleep(1)
print("Starting MDP Solver")
lastPatroller0State = getGroundTruthStateFor(0)
lastPatroller1State = getGroundTruthStateFor(1)
patrollerStartStates = [lastPatroller0State, lastPatroller1State]
patrollerTimes = [0,0]
print("PatrollerStartStates", patrollerStartStates)
print("PatrollerTimes", patrollerTimes, "curRospy", get_time())
args = ["boydattacker", ]
p = subprocess.Popen(args, stdin=subprocess.PIPE, stdout=subprocess.PIPE, stderr=subprocess.PIPE)
# build trajectories
outtraj = self.map + "\n"
outtraj += "false\n"
for stateS in patrollerStartStates:
outtraj += "["
outtraj += str(int(stateS.location[0]))
outtraj += ", "
outtraj += str(int(stateS.location[1]))
outtraj += ", "
outtraj += str(int(stateS.location[1]))
outtraj += "];"
outtraj += "\n"
for startTime in patrollerTimes:
outtraj += str(startTime)
outtraj += ";"
outtraj += "\n"
outtraj += str(1)
outtraj += "\n"
outtraj += str(30)
outtraj += "\n"
outtraj += str(0)
outtraj += "\n"
outtraj += str(10)
outtraj += "\n"
outtraj += str(0)
outtraj += "\n"
outtraj += str(1)
outtraj += "\n"
f = open(get_home() + "/patrolstudy/toupload/patpolicy.log", "w")
f.write(outtraj)
f.close()
(stdout, stderr) = p.communicate(outtraj)
# stdout now needs to be parsed into a hash of state => action, which is then sent to mapagent
pols = []
vs = []
p = {}
v = {}
stateactions = stdout.split("\n")
for stateaction in stateactions:
if (stateaction == "ENDPROBS"):
continue
if len(stateaction) < 2:
# we've found where the marker between two policies
pols.append(p)
vs.append(v)
p = {}
v = {}
continue
temp = stateaction.split(" = ")
if len(temp) < 2: continue
state = temp[0]
value = temp[1]
action = temp[2]
state = state[2 : len(state) - 1]
pieces = state.split(",")
ps = patrol.model.AttackerState(np.array([int(pieces[0]), int(pieces[1][0 : len(pieces[1]) - 1])]) , int(pieces[2]), int(pieces[3]))
if action.strip() == "null":
p[ps] = None
else:
if action.strip() == "AttackerMoveForward":
a = patrol.model.AttackerMoveForward()
elif action.strip() == "AttackerTurnLeft":
a = patrol.model.AttackerTurnLeft()
else:
a = patrol.model.AttackerTurnRight()
p[ps] = a
v[ps] = float(value)
policies = []
for q in pols:
policies.append(mdp.agent.MapAgent(q))
# choose randomly between available goals
# print(policies)
whichone = random.randint(0,len(policies) - 1)
self.policy = policies[whichone]
self.goalState = self.goalStates[whichone]
print("Finished MDP Solving")
def getStateFor(self, position):
global attackerOGMap
return attackerOGMap.toState(position, True)
def getPositionFor(self, mdpState):
global attackerOGMap
return attackerOGMap.toPos(mdpState)
def latestPolicy(self):
return self.policy
def goNow(self):
return fromRospyTime(get_time()) >= fromRospyTime(self.goTime)
def getPatrollerStateActionFor(self, curPos, lastPos, lastPos2, lastTime):
return (0, 1)
def patrollerModel(self):
return FakeModel()
def addPercept(self, patroller, state, time):
pass
def addPerceptFull(self, patroller, state, time):
pass
def getStartState(self):
return self.startState
def getGoalState(self):
return self.goalState
def update(self):
pass
def getModel(self):
return self.model
def classifyAction(outputVec):
global mapToUse
vecs = []
if (mapToUse == "boyd2"):
vecs.append(numpy.array([0.10471529247895256, 0.27178226770618075, 0.33862569390802433, 0.375])) # moveforward
vecs.append(numpy.array([0.5, 0.5, 0.9841229182759271, 0.375])) # turnleft
vecs.append(numpy.array([0.5, 0.5, 0.5, 1.0])) # turnright
vecs.append(numpy.array([0.5, 0.9564354645876385, 0.33862569390802433, 0.375])) # turnaround
vecs.append(numpy.array([0.8952847075210475, 0.27178226770618075, 0.33862569390802433, 0.375])) # stop
else:
# these need to be redone when a NN for boydright is built
vecs.append(numpy.array([0.10471529247895256, 0.27178226770618075, 0.33862569390802433, 0.375])) # moveforward
vecs.append(numpy.array([0.5, 0.5, 0.9841229182759271, 0.375])) # turnleft
vecs.append(numpy.array([0.5, 0.5, 0.5, 1.0])) # turnright
vecs.append(numpy.array([0.5, 0.9564354645876385, 0.33862569390802433, 0.375])) # turnaround
vecs.append(numpy.array([0.8952847075210475, 0.27178226770618075, 0.33862569390802433, 0.375])) # stop
closest = -1
closestVal = sys.float_info.max
for i, v in enumerate(vecs):
dist = numpy.linalg.norm(outputVec - v)
if (dist < closestVal):
closest = i
closestVal = dist
if (closest == 0):
return PatrolActionMoveForward()
if (closest == 1):
return PatrolActionTurnLeft()
if (closest == 2):
return PatrolActionTurnRight()
if (closest == 3):
return PatrolActionTurnAround()
if (closest == 4):
return PatrolActionStop()
return None
def mean_and_variance(data):
n = 0
sum1 = 0
sum2 = 0
for x in data:
n = n + 1
sum1 = sum1 + x
mean = sum1/n
for x in data:
sum2 = sum2 + (x - mean)*(x - mean)
variance = sum2/(n - 1)
return (mean, variance)
actionNN = None
def getPatrollerActionNN(readings):
from pybrain.tools.shortcuts import buildNetwork
from pybrain.structure import TanhLayer
if (len(readings) <= 2):
return None
global actionNN
if (actionNN is None):
global mapTouse
if (mapToUse == "boyd2"):
nnWeights = numpy.array([-0.3304985698,-2.0350233909,1.4252249243,0.2963310102,4.9266064369,-0.1472800993,0.061455457,0.223676191,0.0025171819,-0.517450847,2.543845079,0.2942835103,-0.0823201426,0.3745702746,-0.0281529442,0.2206690533,-0.0985171095,0.0054585868,-36.1536614237,0.0980005071,-10.0402714801,4107.922303848,1.1756230206,-11.173458288,-78.4043090397,1.4706464857,545.5495422035,83336.9157690647,222.1574064718,5.3629004192,-11354.3282550292,482.0961046906,3.627796326,18485.1522666649,3.8994555386,-2.0162859479,-711.4848036675,-0.095789549,-5.1913028932,12165.1412947653,0.9587726743,0.4053123806,20.7827205806,0.3963309953,953.7460206174,41254.089509375,13.8877636884,-55.7693899285,107854.5579788469,-115.024748763,-161.8372335656,-229.7124016302,5.2355727181,-21.1921433795,6814.8934279982,11.8144628413,-1516.9409075926,-178436.1615841909,45.4057518591,-1116.6717947839,-1231.3555799918,26.5367868278,0.2946896214,1107.3431771647,0.0970529269,15.9504145508,1435.8551242887,-0.4690070429,-0.0752631963,-0.7997826301,0.3840072903,0.6206706334,1621.9304807605,-0.1605863922,20.9367198862,5351.8031245516,-0.9362696644,3.1561242116,195.9966687042,-0.1201570823,-4.9454580981,184.8361757175,0.160018912,-33.0211667279,-18176.7060075939,0.871384414,3.5221200995,240.7632822965,-0.2080971545,-1.0405001885,-856.4937261407,0.1298636107,0.5177587901,3069.1714221005,-0.3756751408,-3.9467678449,-33.7275333761,0.040441488,0.132976886,724.3911891873,0.218647283,24.8460698888,2181.8699154502,-0.9915000002,-3.3831296597,10.2921621295,0.7589195007,572.6591220021,32336.6540817552,11.444372836,165.7540263761,-41587.6179129253,-7.3935572673,21.5767608761,-4238.8100528394,36.9535371488,-0.1774941572,1115.1030922934,-0.0162510915,-17.6029184258,2815.2262040795,0.6461238176,1.6241572646,21.2920354298,0.0356162823,0.197993219,-1393.7550083931,0.188329235,10.5948853241,-3788.7678184607,0.2442199395,5.9897149839,-154.4688647851,0.3610844208,-0.0618358173,-0.7957428078,0.3269138991,0.3342662757,-0.2142045179,-0.7582433437,-0.2780321189,0.1074139583,0.0390365181,0.37232585,-0.1611990394,1.1381611431,-0.0017546681,-0.9970171851,-0.0387787452,0.1102100351,0.1756448881,-0.1405135597,-3.407333392,0.2331252469,-0.3326675975,-1.5063271236,2.1723786962,-0.031489985,2.3384290129,1.1644199035,1.0954118938,-0.1759323485,0.2932166683,0.4798292085,-0.4851544844,1.4122326915,-1.2010908245,0.5232572567,1.4147323864,-1.1501400115,-0.1435034775,0.0709863455,-1.6319298998,-0.0440954912,-0.0462593535,0.9498094825,0.0793733352,-0.0069429358,1.6773864397,0.1632380311,0.2338671661,0.6668889845,-0.8915792212,-0.480782618,-0.6649133478,0.0568622766])
else:
# this is totally wrong, but the NN is worse than the manual method so whatever for now
nnWeights = numpy.array([-0.3304985698,-2.0350233909,1.4252249243,0.2963310102,4.9266064369,-0.1472800993,0.061455457,0.223676191,0.0025171819,-0.517450847,2.543845079,0.2942835103,-0.0823201426,0.3745702746,-0.0281529442,0.2206690533,-0.0985171095,0.0054585868,-36.1536614237,0.0980005071,-10.0402714801,4107.922303848,1.1756230206,-11.173458288,-78.4043090397,1.4706464857,545.5495422035,83336.9157690647,222.1574064718,5.3629004192,-11354.3282550292,482.0961046906,3.627796326,18485.1522666649,3.8994555386,-2.0162859479,-711.4848036675,-0.095789549,-5.1913028932,12165.1412947653,0.9587726743,0.4053123806,20.7827205806,0.3963309953,953.7460206174,41254.089509375,13.8877636884,-55.7693899285,107854.5579788469,-115.024748763,-161.8372335656,-229.7124016302,5.2355727181,-21.1921433795,6814.8934279982,11.8144628413,-1516.9409075926,-178436.1615841909,45.4057518591,-1116.6717947839,-1231.3555799918,26.5367868278,0.2946896214,1107.3431771647,0.0970529269,15.9504145508,1435.8551242887,-0.4690070429,-0.0752631963,-0.7997826301,0.3840072903,0.6206706334,1621.9304807605,-0.1605863922,20.9367198862,5351.8031245516,-0.9362696644,3.1561242116,195.9966687042,-0.1201570823,-4.9454580981,184.8361757175,0.160018912,-33.0211667279,-18176.7060075939,0.871384414,3.5221200995,240.7632822965,-0.2080971545,-1.0405001885,-856.4937261407,0.1298636107,0.5177587901,3069.1714221005,-0.3756751408,-3.9467678449,-33.7275333761,0.040441488,0.132976886,724.3911891873,0.218647283,24.8460698888,2181.8699154502,-0.9915000002,-3.3831296597,10.2921621295,0.7589195007,572.6591220021,32336.6540817552,11.444372836,165.7540263761,-41587.6179129253,-7.3935572673,21.5767608761,-4238.8100528394,36.9535371488,-0.1774941572,1115.1030922934,-0.0162510915,-17.6029184258,2815.2262040795,0.6461238176,1.6241572646,21.2920354298,0.0356162823,0.197993219,-1393.7550083931,0.188329235,10.5948853241,-3788.7678184607,0.2442199395,5.9897149839,-154.4688647851,0.3610844208,-0.0618358173,-0.7957428078,0.3269138991,0.3342662757,-0.2142045179,-0.7582433437,-0.2780321189,0.1074139583,0.0390365181,0.37232585,-0.1611990394,1.1381611431,-0.0017546681,-0.9970171851,-0.0387787452,0.1102100351,0.1756448881,-0.1405135597,-3.407333392,0.2331252469,-0.3326675975,-1.5063271236,2.1723786962,-0.031489985,2.3384290129,1.1644199035,1.0954118938,-0.1759323485,0.2932166683,0.4798292085,-0.4851544844,1.4122326915,-1.2010908245,0.5232572567,1.4147323864,-1.1501400115,-0.1435034775,0.0709863455,-1.6319298998,-0.0440954912,-0.0462593535,0.9498094825,0.0793733352,-0.0069429358,1.6773864397,0.1632380311,0.2338671661,0.6668889845,-0.8915792212,-0.480782618,-0.6649133478,0.0568622766])
#build neural net
actionNN = buildNetwork(9, 13, 4, hiddenclass = TanhLayer, outclass = TanhLayer, bias = True)
actionNN._setParameters(nnWeights)
# calculate inputs
deltaxs = []
lastx = None
deltays = []
lasty = None
deltathetas = []
lasttheta = None
for r in readings:
if (lasttheta is not None):
test = r[2] - lasttheta
while (test < -math.pi): test += 2*math.pi;
while (test > math.pi): test -= 2*math.pi;
deltathetas.append(test)
lasttheta = r[2]
if (lastx is not None):
x = math.cos(lasttheta) * (r[0] - lastx) + math.sin(lasttheta)* (r[1] - lasty)
# print("x", msg.pose.pose.position.x, lastx, x, firsttheta)
deltaxs.append(x)
lastx = r[0]
if (lasty is not None):
y = math.sin(lasttheta) * (r[0] - lastx) + math.cos(lasttheta) * (r[1] - lasty)
# print("y", msg.pose.pose.position.y, lasty, y, firsttheta)
deltays.append(y)
lasty = r[1]
sumx = reduce(operator.add, deltaxs, 0)
(meanx, variancex) = mean_and_variance(deltaxs)
sumy = reduce(operator.add, deltays, 0)
(meany, variancey) = mean_and_variance(deltays)
sumtheta = reduce(operator.add, deltathetas, 0)
(meantheta, variancetheta) = mean_and_variance(deltathetas)
return classifyAction(actionNN.activate((meanx, variancex, sumx, meany, variancey, sumy, meantheta, variancetheta, sumtheta)))
def getPatrollerActionForStates(states):
# returns the action that was performed at states[0] to get to states[1] and states[2 - 3] (if given)
if (len(states) <= 1 or states[1] is None):
return PatrolActionMoveForward()
if states[0].location[0] == states[1].location[0] and states[0].location[1] == states[1].location[1]:
# position is the same, have we turned or just stopped?
# check if we've turned
if not (states[0].location[2] == states[1].location[2]):
# if (abs(states[0].location[2] - states[1].location[2]) == 2):
# return PatrolActionTurnAround()
if (states[0].location[2] == 0) and (states[1].location[2] == 3):
return PatrolActionTurnRight()
if (states[0].location[2] == 3) and (states[1].location[2] == 0):
return PatrolActionTurnLeft()
if states[0].location[2] > states[1].location[2]:
return PatrolActionTurnRight()
return PatrolActionTurnLeft()
# nope we're the same, we must've stopped
return PatrolActionStop()
else:
# position is different, check if we moved forward by looking at the orientation
if states[0].location[2] == 0 and (states[0].location[0] == states[1].location[0]) and (states[0].location[1] == states[1].location[1] - 1):
return PatrolActionMoveForward()
if states[0].location[2] == 2 and (states[0].location[0] == states[1].location[0]) and (states[0].location[1] - 1 == states[1].location[1]):
return PatrolActionMoveForward()
if states[0].location[2] == 1 and (states[0].location[0] -1 == states[1].location[0]) and (states[0].location[1] == states[1].location[1]):
return PatrolActionMoveForward()
if states[0].location[2] == 3 and (states[0].location[0] == states[1].location[0] - 1) and (states[0].location[1] == states[1].location[1]):
return PatrolActionMoveForward()
# donno ?
return None
def getPatrollerSubActions(readingsWithinTimestep, state1, state2 ):
actionCount = [0, 0, 0, 0]
for i in range(len(readingsWithinTimestep) - 1):
# calculate angle to turn for point 1 to face point 2
# calculate distance travelled
# calculate angle to turn to final orientation
# calculate the angle between the points
# calculate the amount turned between the current orientation and the intermediate angle
# calculate the amount turned from the intermediate angle to the final one
distance = math.sqrt((readingsWithinTimestep[i][0]-readingsWithinTimestep[i + 1][0])*(readingsWithinTimestep[i][0]-readingsWithinTimestep[i + 1][0]) + (readingsWithinTimestep[i][1]-readingsWithinTimestep[i + 1][1])*(readingsWithinTimestep[i][1]-readingsWithinTimestep[i + 1][1]))
if (distance > 0.0):
diff = math.atan2(readingsWithinTimestep[i + 1][1] - readingsWithinTimestep[i][1], readingsWithinTimestep[i + 1][0] - readingsWithinTimestep[i][0])
else:
diff = 0
if (diff < 0):
diff += 2 * math.pi
angle1 = diff - readingsWithinTimestep[i][2]
while (angle1 < -math.pi/2): angle1 += math.pi;
while (angle1 > math.pi/2): angle1 -= math.pi;
angle2 = readingsWithinTimestep[i + 1][2] - diff
while (angle2 < -math.pi/2): angle2 += math.pi;
while (angle2 > math.pi/2): angle2 -= math.pi;
angle = angle1 + angle2
# angle = readingsWithinTimestep[i + 1][2] - readingsWithinTimestep[i][2]
# while (angle < -3.1415/2): angle += 3.1415;
# while (angle > 3.1415/2): angle -= 3.1415;
# print(str(readingsWithinTimestep[i]) + ", " + str(readingsWithinTimestep[i+1]) + " => " + str(angle) + " " + str(distance))
# classify this action:
# a forward will have good forward movement (duh)
# A stop will have very little forward or angular movement
# A turn will have very little forward movement, but good angular
if (distance < .005) and abs(angle) < 0.03:
actionCount[1] += 1 # stop
elif abs(angle) >= 0.02:
if angle > 0:
actionCount[2] += 1 # leftTurn
else:
actionCount[3] += 1 # rightTurn
else: # .15 meters a second for a tenth of a second
actionCount[0] += 1 # moveforward
return actionCount
def getPatrollerAction(readingsWithinTimestep, state1, state2 ):
states = []
states.append(state1)
states.append(state2)
discreteAction = getPatrollerActionForStates(states)
actionCount = getPatrollerSubActions(readingsWithinTimestep, state1, state2)
# now decide whether to use the discrete-states-calulated action or the substates one
# need to decide if the substates dictate a strong action or not, this really should be done probabilistically, or with a NN, but
# conference paper limits being what they are, we're going to go with something quickly explainable. YAY SCIENCE!
highest = 0
for i in range(len(actionCount)):
if (len(readingsWithinTimestep) > 0):
actionCount[i] /= float(len(readingsWithinTimestep))
if actionCount[i] > actionCount[highest]:
highest = i
# if (len(readingsWithinTimestep) >= (getTimeConv() / 2 / 0.1)) and ((actionCount[2] > 0.7 * len(readingsWithinTimestep) - 1) or (actionCount[3] > 0.7 * len(readingsWithinTimestep) - 1)):
# return PatrolActionTurnAround()
# detect a quick turn left or right by comparing the start and end orientations
# if change >= 90 degrees, it's definitely a turn
if len(readingsWithinTimestep) > 0 and not PatrolActionTurnAround().__eq__(discreteAction):
orientationNet = readingsWithinTimestep[len(readingsWithinTimestep) - 1][2] - readingsWithinTimestep[0][2]
while (orientationNet < -math.pi): orientationNet += math.pi * 2;
while (orientationNet > math.pi): orientationNet -= math.pi * 2;
# if abs(orientationNet) > math.pi / 1.2:
# return PatrolActionTurnAround()
if abs(orientationNet) > math.pi/2.2:
# force a left or right turn
if (orientationNet > 0):
return PatrolActionTurnLeft()
else:
return PatrolActionTurnRight()
# if (actionCount[1]) > 0.5 * len(readingsWithinTimestep) - 1:
# return PatrolActionStop()
# if (actionCount[2] >= 0.25 * len(readingsWithinTimestep) - 1) or (actionCount[3] > 0.25 * len(readingsWithinTimestep) - 1):
# we have a turn
# if actionCount[2] > actionCount[3]:
# return PatrolActionTurnLeft()
# return PatrolActionTurnRight()
if (highest == 0 and (discreteAction is None or (actionCount[highest] > 0.5 and len(readingsWithinTimestep) > 4))):
return PatrolActionMoveForward()
if (highest == 1 and (discreteAction is None or (actionCount[highest] > 0.75 and len(readingsWithinTimestep) > 4))):
return PatrolActionStop()
if (highest == 2 and (discreteAction is None or (actionCount[highest] > 0.75 and len(readingsWithinTimestep) > 4))):
return PatrolActionTurnLeft()
if (highest == 3 and (discreteAction is None or (actionCount[highest] > 0.75 and len(readingsWithinTimestep) > 4))):
return PatrolActionTurnRight()
return discreteAction
def convertObsToDiscreteStates(obsin, traj_begintime):
# convert raw position observations to states
obs = obsin[:]
global patrollerOGMap
discreteStates = []
flag=0
for i in range(traj_begintime, fromRospyTime(get_time())): #(fromRospyTime(get_time())):
flag=1
timeLowerRange = i * getTimeConv()
timeUpperRange = (i + 1) * getTimeConv()
if (len(obs) > 0):
sumObsInTimeStep = [0, 0, 0, 0]
countObsInTimeStep = 0
while (len(obs) > 0 and obs[0][1] >= timeLowerRange and obs[0][1] < timeUpperRange):
# for j in range(len(obsInTimestep) - 1, max(len(obsInTimestep) - numOfReadings - 1, -1), -1):
# for j in range(0, min(len(obsInTimestep), numOfReadings)):
# for j in range(0, len(obsInTimestep)):
curObs = obs.pop(0)[0]
if countObsInTimeStep < 3:
sumObsInTimeStep[0] += curObs[0]
sumObsInTimeStep[1] += curObs[1]
sumObsInTimeStep[2] += math.cos(curObs[2])
sumObsInTimeStep[3] += math.sin(curObs[2])
countObsInTimeStep += 1
if countObsInTimeStep > 0:
avg = [sumObsInTimeStep[0] / countObsInTimeStep, sumObsInTimeStep[1] / countObsInTimeStep, math.atan2(sumObsInTimeStep[3], sumObsInTimeStep[2]) ]
if avg[2] < 0:
avg[2] += 2 * math.pi
s = patrollerOGMap.toState(avg, False)
discreteStates.append(s)
else:
discreteStates.append(None)
discreteStates.append(None)
# if discreteStates==[None] and not not obs:
# print("\n convertObsToDiscreteStates [None] results begin and end times of obsin: "+str(obs[0][1]))
# print(str(obs[len(obs)-1][1]))
# print("\n traj_begintime, fromRospyTime(get_time()): "+str(traj_begintime)+" "+str(fromRospyTime(get_time())))
# print("\n loop enter flag: ", flag)
return discreteStates
def convertObsToTrajectoryWPolicy(obsin, policy):
global glbltrajstarttime
print("glbltrajstarttime in convertObsToTrajectoryWPolicy :", glbltrajstarttime)
discreteStates = convertObsToDiscreteStates(obsin, glbltrajstarttime)
#print("output convertObsToDiscreteStates(obsin, glbltrajstarttime): "+str(discreteStates) )
traj = []
for ds in discreteStates:
if (ds is None):
traj.append(None)
else:
a = policy.actions(ds).keys()[0]
traj.append((ds, a))
return traj
def convertObsToTrajectory(obsin, traj_begintime):
discreteStates = convertObsToDiscreteStates(obsin, traj_begintime)
obs = obsin[:]
traj = []
for i in range(traj_begintime, fromRospyTime(get_time())): #(fromRospyTime(get_time())):
timeLowerRange = i * getTimeConv()
timeUpperRange = (i + 1) * getTimeConv()
obsInTimestep = []
while (len(obs) > 0 and obs[0][1] >= timeLowerRange and obs[0][1] < timeUpperRange):
obsInTimestep.append(obs.pop(0)[0])
if len(obsInTimestep) > 0:
a = getPatrollerAction(obsInTimestep, discreteStates[len(traj)], discreteStates[len(traj) + 1])
traj.append((discreteStates[len(traj)], a))
else:
traj.append(None)
return traj
def convertObsToTrajectoryUncertainActions(obsin):
discreteStates = convertObsToDiscreteStates(obsin)
obs = obsin[:]
traj = []
for i in range(fromRospyTime(get_time())):
timeLowerRange = i * getTimeConv()
timeUpperRange = (i + 1) * getTimeConv()
obsInTimestep = []
while (len(obs) > 0 and obs[0][1] >= timeLowerRange and obs[0][1] < timeUpperRange):
obsInTimestep.append(obs.pop(0)[0])
if len(obsInTimestep) > 0:
a = getPatrollerSubActions(obsInTimestep, discreteStates[len(traj)], discreteStates[len(traj) + 1])
traj.append((discreteStates[len(traj)], a))
else:
traj.append(None)
return traj
def filter_traj_for_t_solver(traj1, traj2):
# remove entries that correspond to interaction states
# remove unmodellable entries by inserting a blank space between them
a = PatrolActionMoveForward()
returnval1 = []
returnval2 = []
for i in range(len(traj1)):
if (i <= 1):
returnval1.append(None)
returnval2.append(None)
continue
if (traj1[i] is not None and traj2[i] is not None):
t1 = a.apply(traj1[i][0])
t2 = a.apply(traj2[i][0])
if (traj1[i][0].conflicts(traj2[i][0])) or (traj1[i][0].conflicts(t2)) or (traj2[i][0].conflicts(t1)):
returnval1.append(None)
returnval2.append(None)
else:
returnval1.append(traj1[i])
returnval2.append(traj2[i])
else:
returnval1.append(traj1[i])
returnval2.append(traj2[i])
return (returnval1, returnval2)
def printTrajectories(trajs):
outtraj = ""
for patroller in trajs:
for sap in patroller:
if (sap is not None):
outtraj += "["
outtraj += str(int(sap[0].location[0]))
outtraj += ", "
outtraj += str(int(sap[0].location[1]))
outtraj += ", "
outtraj += str(int(sap[0].location[2]))
outtraj += "]:"
if sap[1].__class__.__name__ == "PatrolActionMoveForward":
outtraj += "MoveForwardAction"
elif sap[1].__class__.__name__ == "PatrolActionTurnLeft":
outtraj += "TurnLeftAction"
elif sap[1].__class__.__name__ == "PatrolActionTurnRight":
outtraj += "TurnRightAction"
elif sap[1].__class__.__name__ == "PatrolActionTurnAround":
outtraj += "TurnAroundAction"
else:
outtraj += "StopAction"
outtraj += ":"
outtraj += "1"
outtraj += ";"
outtraj += "\n"
outtraj += "ENDTRAJ\n"
return outtraj
def printTrajectoriesStatesOnly(trajs):
outtraj = ""
for patroller in trajs:
for sap in patroller:
if (sap is not None):
outtraj += "["
outtraj += str(int(sap[0].location[0]))
outtraj += ", "
outtraj += str(int(sap[0].location[1]))
outtraj += ", "
outtraj += str(int(sap[0].location[2]))
outtraj += "]"
outtraj += ";"
outtraj += "\nENDTRAJ\n"
return outtraj
def parseTs(stdout):
T = []
t = []
weights = []
transitions = stdout.split("\n")
counter = 0
for transition in transitions:
counter += 1
if transition == "ENDT":
T.append(t)
t = []
continue
temp = transition.split(":")
if temp[0] == "WEIGHTS":
weights.append(temp[1])
continue
if len(temp) < 4: continue
state = temp[0]
action = temp[1]
state_prime = temp[2]
prob = float(temp[3])
state = state[1 : len(state) - 1]
state_prime = state_prime[1 : len(state_prime) - 1]
pieces = state.split(",")
ps = [int(pieces[0]), int(pieces[1]), int(pieces[2])]
pieces = state_prime.split(",")
ps_prime = [int(pieces[0]), int(pieces[1]), int(pieces[2])]
if action == "MoveForwardAction":
a = 0
elif action == "TurnLeftAction":
a = 1
elif action == "TurnRightAction":
a = 2
elif action == "TurnAroundAction":
a = 3
else:
a = 4
t.append( (ps, a, ps_prime, prob))
if (len(t)) > 0:
T.append(t)
while (len(T) < 2):
T.append(T[0])
return (T, weights)
def printTs(T):
outtraj = ""
for t1 in T:
for t in t1:
outtraj += "["
outtraj += str(t[0][0])
outtraj += ", "
outtraj += str(t[0][1])
outtraj += ", "
outtraj += str(t[0][2])
outtraj += "]:"
if t[1] == 0:
outtraj += "MoveForwardAction"
elif t[1] == 1:
outtraj += "TurnLeftAction"
elif t[1] == 2:
outtraj += "TurnRightAction"
elif t[1] == 3:
outtraj += "TurnAroundAction"
else:
outtraj += "StopAction"
outtraj += ":["
outtraj += str(t[2][0])
outtraj += ", "
outtraj += str(t[2][1])
outtraj += ", "
outtraj += str(t[2][2])
outtraj += "]:"
outtraj += str(t[3])
outtraj += "\n"
outtraj += "ENDT\n"
return outtraj
def printStochasticPolicies(pmodel, obs):
# need to convert the observed subactions into distributions over actions for each state, with unseen states being uniform
outtraj = ""
for o in obs:
traj = convertObsToTrajectoryUncertainActions(o)
states = pmodel.S()
action_counts = {}
for s in states:
action_counts[s] = [0, 0, 0, 0]
for entry in traj:
if entry is not None:
for (i, count) in enumerate(entry[1]):
action_counts[entry[0]][i] += count
for (state, counts) in action_counts.iteritems():
total = sum(counts)
if total == 0:
counts = [1 for i in range(len(counts))]
total = len(counts)
for (i, count) in enumerate(counts):
if count > 0:
outtraj += "["
outtraj += str(int(state.location[0]))
outtraj += ", "
outtraj += str(int(state.location[1]))
outtraj += ", "
outtraj += str(int(state.location[2]))
outtraj += "]:"
if i == 0:
outtraj += "MoveForwardAction"
elif i == 1:
outtraj += "StopAction"
elif i == 2:
outtraj += "TurnLeftAction"
else:
outtraj += "TurnRightAction"
outtraj += ":"
outtraj += str(float(count) / float(total))
outtraj += "\n"
outtraj += "ENDPOLICY\n"