This repository has been archived by the owner on May 23, 2023. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 525
/
CombineUnloadAIDriver.lua
2292 lines (1999 loc) · 101 KB
/
CombineUnloadAIDriver.lua
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
--[[
This file is part of Courseplay (https://github.com/Courseplay/courseplay)
Copyright (C) 2020 Thomas Gärtner, Peter Vaiko
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
]]--
--[[
How do we make sure the unloader does not collide with the combine?
1. ProximitySensor
The ProximitySensor is a generic AIDriver feature.
The combine has a proximity sensor on the back and will slow down and stop
if something is in range.
The unloader has a proximity sensor on the front to prevent running into the combine
and to swerve other vehicles in case of a head on collision for example.
In some states, for instance when unloading choppers, the tractor disables the generic
speed control as it has to drive very close to the chopper.
There is an additional proximity sensor dedicated to following the chopper. This has
all controlling features disabled.
2. Turns
The combine stops when discharging during a turn, so at the end of a row or headland turn
it won't start the turn until it is empty.
3. Combine Ready For Unload
The unloader can also ask the combine if it is ready to unload (isReadyToUnload()), as we
expect the combine to know best when it is going to perform some maneuvers.
4. Cooperative Collision Avoidance Using the TrafficController
This is currently screwed up...
]]--
-- TODO: swerve to the correct direction at low angles
-- TODO: move back second unloader when first one moves back
-- TODO: recalculate path when stuck in traffic longer
---@class CombineUnloadAIDriver : AIDriver
CombineUnloadAIDriver = CpObject(AIDriver)
CombineUnloadAIDriver.safetyDistanceFromChopper = 0.75
CombineUnloadAIDriver.targetDistanceBehindChopper = 1
CombineUnloadAIDriver.targetOffsetBehindChopper = 3 -- 3 m to the right
CombineUnloadAIDriver.targetDistanceBehindReversingChopper = 2
CombineUnloadAIDriver.minDistanceFromReversingChopper = 10
CombineUnloadAIDriver.minDistanceFromWideTurnChopper = 5
CombineUnloadAIDriver.minDistanceWhenMovingOutOfWay = 5
CombineUnloadAIDriver.safeManeuveringDistance = 30 -- distance to keep from a combine not ready to unload
CombineUnloadAIDriver.unloaderFollowingDistance = 30 -- distance to keep between two unloaders assigned to the same chopper
CombineUnloadAIDriver.pathfindingRange = 5 -- won't do pathfinding if target is closer than this
CombineUnloadAIDriver.proximitySensorRange = 15
-- Developer hack: to check the class of an object one should use the is_a() defined in CpObject.lua.
-- However, when we reload classes on the fly during the development, the is_a() calls in other modules still
-- have the old class definition (for example CombineUnloadManager.lua) of this class and thus, is_a() fails.
-- Therefore, use this instead, this is safe after a reload.
CombineUnloadAIDriver.isACombineUnloadAIDriver = true
CombineUnloadAIDriver.myStates = {
ON_FIELD = {},
ON_UNLOAD_COURSE =
{checkForTrafficConflict = true, enableProximitySpeedControl = true, enableProximitySwerve = true},
WAITING_FOR_COMBINE_TO_CALL ={},
WAITING_FOR_PATHFINDER= {},
DRIVE_TO_COMBINE =
{checkForTrafficConflict = true, enableProximitySpeedControl = true, enableProximitySwerve = true},
DRIVE_TO_MOVING_COMBINE =
{checkForTrafficConflict = true, enableProximitySpeedControl = true, enableProximitySwerve = true},
DRIVE_TO_FIRST_UNLOADER =
{checkForTrafficConflict = true, enableProximitySpeedControl = true, enableProximitySwerve = true},
DRIVE_TO_UNLOAD_COURSE =
{checkForTrafficConflict = true, enableProximitySpeedControl = true, enableProximitySwerve = true},
UNLOADING_MOVING_COMBINE = {},
UNLOADING_STOPPED_COMBINE = {},
FOLLOW_CHOPPER =
{isUnloadingChopper = true, enableProximitySpeedControl = true},
FOLLOW_FIRST_UNLOADER =
{checkForTrafficConflict = true},
MOVE_BACK_FROM_REVERSING_CHOPPER =
{isUnloadingChopper = true},
MOVE_BACK_FROM_EMPTY_COMBINE = {},
MOVE_BACK_FULL = {},
HANDLE_CHOPPER_HEADLAND_TURN = {isUnloadingChopper = true, isHandlingChopperTurn = true},
HANDLE_CHOPPER_180_TURN =
{isUnloadingChopper = true, isHandlingChopperTurn = true, enableProximitySpeedControl = true},
FOLLOW_CHOPPER_THROUGH_TURN =
{isUnloadingChopper = true, isHandlingChopperTurn = true, enableProximitySpeedControl = true},
ALIGN_TO_CHOPPER_AFTER_TURN =
{isUnloadingChopper = true, isHandlingChopperTurn = true, enableProximitySpeedControl = true},
MOVING_OUT_OF_WAY = {isUnloadingChopper = true},
WAITING_FOR_MANEUVERING_COMBINE = {},
ON_UNLOAD_WITH_AUTODRIVE = {},
}
--- Constructor
function CombineUnloadAIDriver:init(vehicle)
courseplay.debugVehicle(courseplay.DBG_AI_DRIVER,vehicle,'CombineUnloadAIDriver:init()')
self.assignedCombinesSetting = AssignedCombinesSetting(vehicle)
AIDriver.init(self, vehicle)
self.debugChannel = courseplay.DBG_MODE_2
self.mode = courseplay.MODE_COMBI
self:initStates(CombineUnloadAIDriver.myStates)
self.combineOffset = 0
self.distanceToCombine = math.huge
self.distanceToFront = 0
self.combineToUnloadReversing = 0
self.doNotSwerveForVehicle = CpTemporaryObject()
self.justFinishedPathfindingForDistance = CpTemporaryObject()
self.isRecoveringFromDeadlock = CpTemporaryObject()
end
function CombineUnloadAIDriver:getAssignedCombines()
return self.assignedCombinesSetting:getData()
end
function CombineUnloadAIDriver:getAssignedCombinesSetting()
return self.assignedCombinesSetting
end
function CombineUnloadAIDriver:setHudContent()
AIDriver.setHudContent(self)
courseplay.hud:setCombineUnloadAIDriverContent(self.vehicle,self.assignedCombinesSetting)
end
function CombineUnloadAIDriver:onWriteStream(streamId)
self.assignedCombinesSetting:onWriteStream(streamId)
AIDriver.onWriteStream(self,streamId)
end
function CombineUnloadAIDriver:onReadStream(streamId)
self.assignedCombinesSetting:onReadStream(streamId)
AIDriver.onReadStream(self,streamId)
end
function CombineUnloadAIDriver:debug(...)
local combineName = self.combineToUnload and (' -> ' .. nameNum(self.combineToUnload)) or '(unassigned)'
courseplay.debugVehicle(self.debugChannel, self.vehicle, combineName .. ': ' .. string.format( ... ))
end
function CombineUnloadAIDriver:showPathfinderResult(path, goalNodeInvalid, ...)
local pathfinderRuntimeMs = self.vehicle.timer - (self.pathfindingStartedAt or self.vehicle.timer)
if goalNodeInvalid then
self:debug(string.format('Pathfinder result: failed after %d ms, goal node invalid, ', pathfinderRuntimeMs) ..
string.format(...))
elseif path == nil or #path < 2 then
self:debug(string.format('Pathfinder result: failed after %d ms, no path found, ', pathfinderRuntimeMs) ..
string.format(...))
else
self:debug(string.format('Pathfinder result: successful after %d ms, ', pathfinderRuntimeMs) ..
string.format(...))
end
end
function CombineUnloadAIDriver:start(startingPoint)
self:beforeStart()
-- disable the legacy collision detection snake
self:disableCollisionDetection()
self:resetPathfinder()
self:addChopperProximitySensor()
self.state = self.states.RUNNING
self.unloadCourse = Course(self.vehicle, self.vehicle.Waypoints)
self.ppc:setNormalLookaheadDistance()
self:setDriveUnloadNow(false)
if startingPoint:is(StartingPointSetting.START_WITH_UNLOAD) then
if CpManager.isDeveloper then
-- automatically select closest combine
self.assignedCombinesSetting:selectClosest()
end
self:info('Start unloading, waiting for a combine to call')
self:setNewState(self.states.ON_FIELD)
self:disableCollisionDetection()
self:startWaitingForCombine()
else
-- just to have a course set up in any case for PPC to work with until we find a combine/path
self:startCourse(self.unloadCourse, 1)
local ix = self.unloadCourse:getStartingWaypointIx(AIDriverUtil.getDirectionNode(self.vehicle), startingPoint)
self:info('AI driver in mode %d starting at %d/%d waypoints (%s)',
self:getMode(), ix, self.unloadCourse:getNumberOfWaypoints(), tostring(startingPoint))
self:startCourseWithPathfinding(self.unloadCourse, ix, 0, 0)
self:setNewState(self.states.ON_UNLOAD_COURSE)
end
self.distanceToFront = 0
end
function CombineUnloadAIDriver:dismiss()
local x,_,z = getWorldTranslation(self:getDirectionNode())
if self.combineToUnload then
self.combineToUnload.cp.driver:deregisterUnloader(self)
end
self:releaseUnloader()
if courseplay:isField(x, z) then
self:setNewState(self.states.ON_FIELD)
self:startWaitingForCombine()
end
AIDriver.dismiss(self)
end
function CombineUnloadAIDriver:drive(dt)
courseplay:updateFillLevelsAndCapacities(self.vehicle)
self:updateCombineStatus()
if self.state == self.states.ON_UNLOAD_COURSE then
self:driveUnloadCourse(dt)
self:enableFillTypeUnloading()
elseif self.state == self.states.ON_FIELD then
self.triggerHandler:disableFillTypeUnloading()
local renderOffset = self.vehicle.cp.coursePlayerNum * 0.03
self:renderText(0, 0.1 + renderOffset, "%s: self.onFieldState :%s", nameNum(self.vehicle), self.onFieldState.name)
self:driveOnField(dt)
elseif self.state == self.states.ON_UNLOAD_WITH_AUTODRIVE then
-- AutoDrive is driving, don't call AIDriver.drive()
return
end
end
--enables unloading for CombineUnloadAIDriver with triggerHandler, but gets overwritten by OverloaderAIDriver, as it's not needed for it.
function CombineUnloadAIDriver:enableFillTypeUnloading()
self.triggerHandler:enableFillTypeUnloading()
self.triggerHandler:enableFillTypeUnloadingBunkerSilo()
end
function CombineUnloadAIDriver:driveUnloadCourse(dt)
-- TODO: refactor that whole unload process, it was just copied from the legacy CP code
self:searchForTipTriggers()
local allowedToDrive, giveUpControl = self:onUnLoadCourse(true, dt)
if not allowedToDrive then
self:hold()
end
if not giveUpControl then
AIDriver.drive(self, dt)
end
end
function CombineUnloadAIDriver:resetPathfinder()
self.maxFruitPercent = 10
-- prefer driving on field, don't do this too aggressively until we take into account the field owner
-- otherwise we'll be driving through others' fields
self.offFieldPenalty = PathfinderUtil.defaultOffFieldPenalty
self.pathfinderFailureCount = 0
end
function CombineUnloadAIDriver:addForwardProximitySensor()
self:setFrontMarkerNode(self.vehicle)
self.forwardLookingProximitySensorPack = WideForwardLookingProximitySensorPack(
self.vehicle, self.ppc, self:getFrontMarkerNode(self.vehicle), self.proximitySensorRange, 1, 2)
end
--- Proximity sensor to check the chopper's distance
function CombineUnloadAIDriver:addChopperProximitySensor()
self:setFrontMarkerNode(self.vehicle)
---@type ProximitySensorPack
self.chopperProximitySensorPack = ProximitySensorPack('chopper',
self.vehicle, self.ppc, self:getFrontMarkerNode(self.vehicle), 10, 1.2, {0, 45, 90, -45, -90}, {0, 0, 0, 0, 0})
self.chopperProximitySensorPack:disableRotateToGoalPoint()
end
function CombineUnloadAIDriver:isTrafficConflictDetectionEnabled()
return self.trafficConflictDetectionEnabled and
(self.state == self.states.ON_UNLOAD_COURSE and self.state.properties.checkForTrafficConflict) or
(self.state == self.states.ON_FIELD and self.onFieldState.properties.checkForTrafficConflict)
end
function CombineUnloadAIDriver:isProximitySwerveEnabled(vehicle)
if vehicle == self.doNotSwerveForVehicle:get() then return false end
return (self.state == self.states.ON_UNLOAD_COURSE and self.state.properties.enableProximitySwerve) or
(self.state == self.states.ON_FIELD and self.onFieldState.properties.enableProximitySwerve)
end
function CombineUnloadAIDriver:isProximitySpeedControlEnabled()
return (self.state == self.states.ON_UNLOAD_COURSE and self.state.properties.enableProximitySpeedControl) or
(self.state == self.states.ON_FIELD and self.onFieldState.properties.enableProximitySpeedControl)
end
function CombineUnloadAIDriver:isWaitingForAssignment()
return self.state == self.states.ON_FIELD and self.onFieldState == self.states.WAITING_FOR_COMBINE_TO_CALL
end
function CombineUnloadAIDriver:startWaitingForCombine()
-- to always have a valid course (for the traffic conflict detector mainly)
self:startCourse(self:getStraightForwardCourse(25), 1)
self:setNewOnFieldState(self.states.WAITING_FOR_COMBINE_TO_CALL)
end
-- we want to come to a hard stop while the base class pathfinder is running (starting a course with pathfinding),
-- because the way AIDriver works, it'll initialize the PPC to the new course/waypoint, which will turn the
-- vehicle's wheels in that direction, and since setting speed to 0 will just let the vehicle roll for a while
-- it may be running into something (like the combine)
function CombineUnloadAIDriver:stopForPathfinding()
self:hold()
end
function CombineUnloadAIDriver:driveInDirection(dt,lx,lz,fwd,speed,allowedToDrive)
--AIVehicleUtil.driveInDirection(self.vehicle, dt, self.vehicle.cp.steeringAngle, 1, 0.5, 10, allowedToDrive, fwd, lx, lz, speed, 1)
-- TODO: use this directly everywhere, seems to work better than the vanilla AIVehicleUtil version
self:driveVehicleInDirection(dt, allowedToDrive, fwd, lx, lz, speed)
end
function CombineUnloadAIDriver:driveOnField(dt)
self:drawDebugInfo()
-- make sure if we have a combine we stay registered
if self.combineToUnload then
self.combineToUnload.cp.driver:registerUnloader(self)
end
-- safety check: combine has active AI driver
if self.combineToUnload and not self.combineToUnload.cp.driver:isActive() then
self:setSpeed(0)
elseif self.vehicle.cp.settings.forcedToStop:is(true) then
self:setSpeed(0)
elseif self.onFieldState == self.states.WAITING_FOR_COMBINE_TO_CALL then
local combineToWaitFor
if self:getDriveUnloadNow() or self:getAllTrailersFull() or self:shouldDriveOn() then
self:debug('Was waiting for a combine but drive now requested or trailer full')
self:startUnloadCourse()
return
end
-- check for an available combine but not in every loop, not needed
if g_updateLoopIndex % 100 == 0 then
self:debug('Check if there\'s a combine to unload, %s', self:getAssignedCombinesSetting())
self.combineToUnload, combineToWaitFor = g_combineUnloadManager:giveMeACombineToUnload(self.vehicle)
if self.combineToUnload ~= nil then
self:refreshHUD()
self:openCovers(self.vehicle)
self:startWorking()
else
if combineToWaitFor then
courseplay:setInfoText(self.vehicle, string.format("COURSEPLAY_WAITING_FOR_FILL_LEVEL;%s", nameNum(combineToWaitFor)));
else
courseplay:setInfoText(self.vehicle, "COURSEPLAY_NO_COMBINE_IN_REACH");
end
end
end
--- This should re enable fuel save, when the driver is waiting for combines to call.
-- self:hold()
self:holdWithFuelSave()
elseif self.onFieldState == self.states.WAITING_FOR_PATHFINDER then
-- just wait for the pathfinder to finish
self:setSpeed(0)
elseif self.onFieldState == self.states.DRIVE_TO_FIRST_UNLOADER then
-- previous first unloader not unloading anymore
if self:iAmFirstUnloader() then
-- switch to drive to chopper or following chopper
self:startWorking()
end
self:setFieldSpeed()
if self:isOkToStartFollowingFirstUnloader() then
self:startFollowingFirstUnloader()
end
elseif self.onFieldState == self.states.WAITING_FOR_FIRST_UNLOADER then
-- wait to become first unloader or until first unloader can be followed
if self:iAmFirstUnloader() then
-- switch to drive to chopper or following chopper
self:startWorking()
end
self:setSpeed(0)
if self:isOkToStartFollowingFirstUnloader() then
self:startFollowingFirstUnloader()
end
elseif self.onFieldState == self.states.DRIVE_TO_COMBINE then
self:driveToCombine()
elseif self.onFieldState == self.states.DRIVE_TO_MOVING_COMBINE then
self:driveToMovingCombine()
elseif self.onFieldState == self.states.UNLOADING_STOPPED_COMBINE then
self:unloadStoppedCombine()
elseif self.onFieldState == self.states.WAITING_FOR_MANEUVERING_COMBINE then
self:waitForManeuveringCombine()
elseif self.onFieldState == self.states.MOVING_OUT_OF_WAY then
self:moveOutOfWay()
elseif self.onFieldState == self.states.UNLOADING_MOVING_COMBINE then
self:disableProximitySpeedControl()
self:disableProximitySwerve()
self:unloadMovingCombine(dt)
elseif self.onFieldState == self.states.FOLLOW_CHOPPER then
self:followChopper()
elseif self.onFieldState == self.states.FOLLOW_FIRST_UNLOADER then
self:followFirstUnloader()
elseif self.onFieldState == self.states.HANDLE_CHOPPER_HEADLAND_TURN then
self:handleChopperHeadlandTurn()
elseif self.onFieldState == self.states.HANDLE_CHOPPER_180_TURN then
self:handleChopper180Turn()
elseif self.onFieldState == self.states.ALIGN_TO_CHOPPER_AFTER_TURN then
self:alignToChopperAfterTurn()
elseif self.onFieldState == self.states.FOLLOW_CHOPPER_THROUGH_TURN then
self:followChopperThroughTurn()
elseif self.onFieldState == self.states.DRIVE_TO_UNLOAD_COURSE then
self:setFieldSpeed()
-- try not crashing into our combine on the way to the unload course
if self.combineJustUnloaded and
not self.combineJustUnloaded.cp.driver:isChopper() and
self:isWithinSafeManeuveringDistance(self.combineJustUnloaded) and
self.combineJustUnloaded.cp.driver:isManeuvering() then
self:debugSparse('holding for maneuvering combine %s on the unload course', self.combineJustUnloaded:getName())
--self.combineJustUnloaded.cp.driver:hold()
end
elseif self.onFieldState == self.states.MOVE_BACK_FULL then
local _, dx, dz = self:getDistanceFromCombine(self.combineJustUnloaded)
-- drive back way further if we are behind a chopper to have room
local dDriveBack = math.abs(dx) < 3 and 0.75 * self.settings.turnDiameter:get() or -10
if dz > dDriveBack then
self:startUnloadCourse()
end
elseif self.onFieldState == self.states.MOVE_BACK_FROM_EMPTY_COMBINE then
-- drive back until the combine is in front of us
local _, _, dz = self:getDistanceFromCombine(self.combineJustUnloaded)
if dz > 0 then
self:startWaitingForCombine()
end
elseif self.onFieldState == self.states.MOVE_BACK_FROM_REVERSING_CHOPPER then
self:renderText(0, 0, "drive straight reverse :offset local :%s saved:%s", tostring(self.combineOffset), tostring(self.settings.combineOffsetX:get()))
local d = self:getDistanceFromCombine()
local combineSpeed = (self.combineToUnload.lastSpeedReal * 3600)
local speed = combineSpeed + MathUtil.clamp(self.minDistanceFromReversingChopper - d, -combineSpeed, self.vehicle.cp.speeds.reverse * 1.5)
self:renderText(0, 0.7, 'd = %.1f, distance diff = %.1f speed = %.1f', d, self.minDistanceFromReversingChopper - d, speed)
-- keep 15 m distance from chopper
self:setSpeed(speed)
if not self:isMyCombineReversing() then
-- resume forward course
self:startCourse(self.followCourse, self.followCourse:getCurrentWaypointIx())
self:setNewOnFieldState(self.states.HANDLE_CHOPPER_HEADLAND_TURN)
end
end
AIDriver.drive(self, dt)
end
function CombineUnloadAIDriver:setCombineToUnloadClient(combineToUnload)
self.combineToUnload = combineToUnload
self.combineToUnload.cp.driver:registerUnloader(self.vehicle)
end
function CombineUnloadAIDriver:getTractorsFillLevelPercent()
return self.tractorToFollow.cp.totalFillLevelPercent
end
function CombineUnloadAIDriver:getFillLevelPercent()
return self.vehicle.cp.totalFillLevelPercent
end
function CombineUnloadAIDriver:getNominalSpeed()
if self.state == self.states.ON_UNLOAD_COURSE then
return self:getRecordedSpeed()
else
return self:getFieldSpeed()
end
end
function CombineUnloadAIDriver:driveBesideCombine()
-- we don't want a moving target
self:fixAutoAimNode()
local targetNode = self:getTrailersTargetNode()
local _, offsetZ = self:getPipeOffset(self.combineToUnload)
-- TODO: this - 1 is a workaround the fact that we use a simple P controller instead of a PI
local _, _, dz = localToLocal(targetNode, self:getCombineRootNode(), 0, 0, - offsetZ - 1)
-- use a factor to make sure we reach the pipe fast, but be more gentle while discharging
local factor = self.combineToUnload.cp.driver:isDischarging() and 0.5 or 2
local speed = self.combineToUnload.lastSpeedReal * 3600 + MathUtil.clamp(-dz * factor, -10, 15)
-- slow down while the pipe is unfolding to avoid crashing onto it
if self.combineToUnload.cp.driver:isPipeMoving() then
speed = (math.min(speed, self.combineToUnload:getLastSpeed() + 2))
end
self:renderText(0, 0.02, "%s: driveBesideCombine: dz = %.1f, speed = %.1f, factor = %.1f",
nameNum(self.vehicle), dz, speed, factor)
if courseplay.debugChannels[self.debugChannel] then
DebugUtil.drawDebugNode(targetNode, 'target')
end
self:setSpeed(math.max(0, speed))
end
function CombineUnloadAIDriver:driveBesideChopper()
local targetNode = self:getTrailersTargetNode()
self:renderText(0, 0.02,"%s: driveBesideChopper:offset local :%s saved:%s",nameNum(self.vehicle),tostring(self.combineOffset),tostring(self.settings.combineOffsetX:get()))
self:releaseAutoAimNode()
local _, _, dz = localToLocal(targetNode, self:getCombineRootNode(), 0, 0, 5)
self:setSpeed(math.max(0, (self.combineToUnload.lastSpeedReal * 3600) + (MathUtil.clamp(-dz, -10, 15))))
end
function CombineUnloadAIDriver:driveBehindChopper()
self:renderText(0, 0.05, "%s: driveBehindChopper offset local :%s saved:%s",nameNum(self.vehicle),tostring(self.combineOffset),tostring(self.settings.combineOffsetX:get()))
self:fixAutoAimNode()
--get required Speed
self:setSpeed(self:getSpeedBehindChopper())
end
function CombineUnloadAIDriver:onEndCourse()
if self.state == self.states.ON_UNLOAD_COURSE or self.state == self.states.ON_UNLOAD_WITH_AUTODRIVE then
self:setNewState(self.states.ON_FIELD)
self:startWaitingForCombine()
self:setDriveUnloadNow(false)
self:openCovers(self.vehicle)
self:disableCollisionDetection()
end
end
function CombineUnloadAIDriver:onLastWaypoint()
if self.state == self.states.ON_FIELD then
if self.onFieldState == self.states.DRIVE_TO_UNLOAD_COURSE then
self:setNewState(self.states.ON_UNLOAD_COURSE)
self:closeCovers(self.vehicle)
AIDriver.onLastWaypoint(self)
return
elseif self.onFieldState == self.states.DRIVE_TO_FIRST_UNLOADER then
self:startDrivingToChopper()
elseif self.onFieldState == self.states.DRIVE_TO_COMBINE or
self.onFieldState == self.states.DRIVE_TO_MOVING_COMBINE then
self:startWorking()
elseif self.onFieldState == self.states.MOVING_OUT_OF_WAY then
self:setNewOnFieldState(self.stateAfterMovedOutOfWay)
end
end
AIDriver.onLastWaypoint(self)
end
-- if closer than this to the last waypoint, start slowing down
function CombineUnloadAIDriver:getSlowDownDistanceBeforeLastWaypoint()
local d = AIDriver.defaultSlowDownDistanceBeforeLastWaypoint
-- in some states there's no need to slow down before reaching the last waypoints
if self.state == self.states.ON_FIELD then
if self.onFieldState == self.states.DRIVE_TO_FIRST_UNLOADER then
d = 0
else
-- in general, be more bold than the standard AI Driver to not waste time for rendezvous
d = AIDriver.defaultSlowDownDistanceBeforeLastWaypoint / 3
end
end
return d
end
function CombineUnloadAIDriver:setFieldSpeed()
if self.course then
self:setSpeed(self:getFieldSpeed())
end
end
function CombineUnloadAIDriver:setNewState(newState)
self.state = newState
self:debug('setNewState: %s', self.state.name)
end
function CombineUnloadAIDriver:setNewOnFieldState(newState)
self.onFieldState = newState
self:debug('setNewOnFieldState: %s', self.onFieldState.name)
end
function CombineUnloadAIDriver:getCourseToAlignTo(vehicle,offset)
local waypoints = {}
for i=-20,20,5 do
local x,y,z = localToWorld(vehicle.rootNode,offset,0,i)
local point = { cx = x;
cy = y;
cz = z;
}
table.insert(waypoints,point)
end
local tempCourse = Course(self.vehicle,waypoints)
return tempCourse
end
function CombineUnloadAIDriver:getTrailersTargetNode()
local allTrailersFull = true
for i=1, #self.vehicle.cp.workTools do
local tipper = self.vehicle.cp.workTools[i]
local fillUnits = tipper:getFillUnits()
for j=1, #fillUnits do
local tipperFillType = tipper:getFillUnitFillType(j)
local combineFillType = self.combineToUnload and self.combineToUnload.cp.driver.combine:getFillUnitLastValidFillType(self.combineToUnload.cp.driver.combine:getCurrentDischargeNode().fillUnitIndex) or FillType.UNKNOWN
if tipper:getFillUnitFreeCapacity(j) > 0 then
allTrailersFull = false
if tipperFillType == FillType.UNKNOWN or tipperFillType == combineFillType or combineFillType == FillType.UNKNOWN then
local targetNode = tipper:getFillUnitAutoAimTargetNode(1)
if targetNode then
return targetNode, allTrailersFull
else
return tipper.rootNode, allTrailersFull
end
end
end
end
end
self:debugSparse('Can\'t find trailer target node')
return self.vehicle.cp.workTools[1].rootNode, allTrailersFull
end
function CombineUnloadAIDriver:getSpeedBesideChopper(targetNode)
local allowedToDrive = true
local baseNode = self:getPipesBaseNode(self.combineToUnload)
--Discharge Node to AutoAimNode
local wx, wy, wz = getWorldTranslation(targetNode)
--cpDebug:drawLine(dnX,dnY,dnZ, 100, 100, 100, wx,wy,wz)
-- pipe's local position in the trailer's coordinate system
local dx,_,dz = worldToLocal(baseNode, wx, wy, wz)
--am I too far in front but beside the chopper ?
if dz < 3 and math.abs(dx)< math.abs(self:getSavedCombineOffset())+1 then
allowedToDrive = false
end
-- negative speeds are invalid
return math.max(0, (self.combineToUnload.lastSpeedReal * 3600) + (MathUtil.clamp(-dz, -10, 15))), allowedToDrive
end
function CombineUnloadAIDriver:getSpeedBesideCombine(targetNode)
end
function CombineUnloadAIDriver:getSpeedBehindCombine()
if self.distanceToFront == 0 then
self:raycastFront()
return 0
else
self:raycastDistance(30)
end
local targetGap = 20
local targetDistance = self.distanceToCombine - targetGap
return (self.combineToUnload.lastSpeedReal * 3600) +(MathUtil.clamp(targetDistance,-10,15))
end
function CombineUnloadAIDriver:getSpeedBehindChopper()
local distanceToChoppersBack, _, dz = self:getDistanceFromCombine()
local fwdDistance = self.chopperProximitySensorPack:getClosestObjectDistanceAndRootVehicle()
if dz < 0 then
-- I'm way too forward, stop here as I'm most likely beside the chopper, let it pass before
-- moving to the middle
self:setSpeed(0)
end
local errorSafety = self.safetyDistanceFromChopper - fwdDistance
local errorTarget = self.targetDistanceBehindChopper - dz
local error = math.abs(errorSafety) < math.abs(errorTarget) and errorSafety or errorTarget
local deltaV = MathUtil.clamp(-error * 2, -10, 15)
local speed = (self.combineToUnload.lastSpeedReal * 3600) + deltaV
self:renderText(0, 0.7, 'd = %.1f, dz = %.1f, speed = %.1f, errSafety = %.1f, errTarget = %.1f',
distanceToChoppersBack, dz, speed, errorSafety, errorTarget)
return speed
end
function CombineUnloadAIDriver:getOffsetBehindChopper()
local distanceToChoppersBack, dx, dz = self:getDistanceFromCombine()
local rightDistance = self.chopperProximitySensorPack:getClosestObjectDistanceAndRootVehicle(-90)
local fwdRightDistance = self.chopperProximitySensorPack:getClosestObjectDistanceAndRootVehicle(-45)
local minDistance = math.min(rightDistance, fwdRightDistance / 1.4)
local currentOffsetX, _ = self.followCourse:getOffset()
-- TODO: course offset seems to be inverted
currentOffsetX = - currentOffsetX
local error
if dz < 0 and minDistance < 1000 then
-- proximity sensor in range, use that to adjust our target offset
-- TODO: use actual vehicle width instead of magic constant (we need to consider vehicle width
-- as the proximity sensor is in the middle
error = (self.safetyDistanceFromChopper + 1) - minDistance
self.targetOffsetBehindChopper = MathUtil.clamp(self.targetOffsetBehindChopper + 0.02 * error, -20, 20)
self:debug('err %.1f target %.1f', error, self.targetOffsetBehindChopper)
end
error = self.targetOffsetBehindChopper - currentOffsetX
local newOffset = currentOffsetX + error * 0.2
self:renderText(0, 0.68, 'right = %.1f, fwdRight = %.1f, current = %.1f, err = %1.f',
rightDistance, fwdRightDistance, currentOffsetX, error)
self:debug('right = %.1f, fwdRight = %.1f, current = %.1f, err = %1.f',
rightDistance, fwdRightDistance, currentOffsetX, error)
return MathUtil.clamp(-newOffset, -50, 50)
end
function CombineUnloadAIDriver:getSpeedBehindTractor(tractorToFollow)
local targetDistance = 35
local diff = courseplay:distanceToObject(self.vehicle, tractorToFollow) - targetDistance
return math.min(self:getFieldSpeed(),(tractorToFollow.lastSpeedReal*3600) +(MathUtil.clamp( diff,-10,25)))
end
function CombineUnloadAIDriver:getPipesBaseNode(combine)
return g_combineUnloadManager:getPipesBaseNode(combine)
end
function CombineUnloadAIDriver:getCombineIsTurning()
return self.combineToUnload.cp.driver and self.combineToUnload.cp.driver:isTurning()
end
-- TODO: remove this legacy function and use getPipeOffset everywhere
function CombineUnloadAIDriver:getCombineOffset(combine)
return g_combineUnloadManager:getCombinesPipeOffset(combine)
end
---@return number, number x and z offset of the pipe's end from the combine's root node in the Giants coordinate system
---(x > 0 left, z > 0 forward) corrected with the manual offset settings
function CombineUnloadAIDriver:getPipeOffset(combine)
return combine.cp.driver:getPipeOffset(-self.settings.combineOffsetX:get(), self.settings.combineOffsetZ:get())
end
function CombineUnloadAIDriver:getChopperOffset(combine)
local pipeOffset = g_combineUnloadManager:getCombinesPipeOffset(combine)
local leftOk, rightOk = g_combineUnloadManager:getPossibleSidesToDrive(combine)
local currentOffset = self.combineOffset
local newOffset = currentOffset
-- fruit on both sides, stay behind the chopper
if not leftOk and not rightOk then
newOffset = 0
elseif leftOk and not rightOk then
-- no fruit to the left
if currentOffset >= 0 then
-- we are already on the left or middle, go to left
newOffset = pipeOffset
else
-- we are on the right, move to the middle
newOffset = 0
end
elseif not leftOk and rightOk then
-- no fruit to the right
if currentOffset <= 0 then
-- we are already on the right or in the middle, move to the right
newOffset = -pipeOffset
else
-- we are on the left, move to the middle
newOffset = 0
end
end
if newOffset ~= currentOffset then
self:debug('Change combine offset: %.1f -> %.1f (pipe %.1f), leftOk: %s rightOk: %s',
currentOffset, newOffset, pipeOffset, tostring(leftOk), tostring(rightOk))
end
return newOffset
end
function CombineUnloadAIDriver:setSavedCombineOffset(newOffset)
if self.settings.combineOffsetX:get() == 0 then
self.settings.combineOffsetX:set(newOffset)
self:refreshHUD()
return newOffset
else
--TODO Handle manual offsets
end
end
function CombineUnloadAIDriver:getSavedCombineOffset()
if self.settings.combineOffsetX:get() then
return self.settings.combineOffsetX:get()
end
-- else???? this does not make any sense, this is still just a nil ...
end
function CombineUnloadAIDriver:raycastFront()
local nx, ny, nz = localDirectionToWorld(self:getDirectionNode(), 0, 0, -1)
self.distanceToFront = 0
for x=-1.5,1.5,0.1 do
for y=0.2,3,0.1 do
local rx,ry,rz = localToWorld(self.vehicle.cp.directionNode, x, y, 10)
raycastAll(rx, ry, rz, nx, ny, nz, 'raycastFrontCallback', 10, self)
end
end
print(string.format("%s: self.distanceToFront(%s)",nameNum(self.vehicle),tostring(self.distanceToFront)))
end
function CombineUnloadAIDriver:raycastFrontCallback(hitObjectId, x, y, z, distance, nx, ny, nz, subShapeIndex)
if hitObjectId ~= 0 then
local object = g_currentMission:getNodeObject(hitObjectId)
if object and object == self.vehicle then
local frontDistance = 10 - distance
if self.distanceToFront < frontDistance then
self.distanceToFront = frontDistance
end
local colliNode = self.vehicle.cp.driver.collisionDetector.trafficCollisionTriggers[1]
local nodeX,nodeY,nodeZ = getWorldTranslation(colliNode)
local _,_,sz = worldToLocal(self:getDirectionNode(),nodeX,nodeY,nodeZ)
local Tx,Ty,Tz = getTranslation(colliNode,self:getDirectionNode());
if sz < self.distanceToFront+0.1 then
setTranslation(colliNode, Tx,Ty,Tz+(self.distanceToFront+0.1-sz))
end
else
return true
end
end
end
-- This all seems to be here to figure out how far we are from the combine
-- looks too complicated and fragile as it is using the collisionDetector internals and who knows where that
-- is in any moment.
function CombineUnloadAIDriver:raycastDistance(maxDistance)
self.distanceToCombine = math.huge
local colliNode = self.vehicle.cp.driver.collisionDetector.trafficCollisionTriggers[1]
local nodeX, nodeY, nodeZ = getWorldTranslation(colliNode)
local gx,gy,gz = localToWorld(self.combineToUnload.cp.directionNode,0,0, -(self:getCombinesMeasuredBackDistance()))
local lx,lz = AIVehicleUtil.getDriveDirection(colliNode, gx,gy,gz)
local terrain = getTerrainHeightAtWorldPos(g_currentMission.terrainRootNode, gx, 1, gz);
local nx, ny, nz = localDirectionToWorld(colliNode, lx, 0, lz)
--cpDebug:drawLine(nodeX, nodeY, nodeZ, 100, 100, 100, nodeX+(nx*distance), nodeY+(ny*distance), nodeZ+(nz*distance))
for i=1,3 do
raycastAll(nodeX, terrain+i, nodeZ, nx, ny, nz, 'raycastDistanceCallback', maxDistance, self)
end
end
function CombineUnloadAIDriver:raycastDistanceCallback(hitObjectId, x, y, z, distance, nx, ny, nz, subShapeIndex)
if hitObjectId ~= 0 then
--print(string.format("%s in %s m",tostring(getName(hitObjectId)),tostring(distance)))
local object = g_currentMission:getNodeObject(hitObjectId)
if object and object == self.combineToUnload then
cpDebug:drawPoint(x, y, z, 1, 1 , 1);
self.distanceToCombine = math.min(distance,self.distanceToCombine)
else
return true
end
end
end
function CombineUnloadAIDriver:getCombinesMeasuredBackDistance()
return self.combineToUnload.cp.driver:getMeasuredBackDistance()
end
function CombineUnloadAIDriver:getCanShowDriveOnButton()
return self.state == self.states.ON_FIELD or AIDriver.getCanShowDriveOnButton(self)
end
function CombineUnloadAIDriver:setDriveNow()
if self.state == self.states.ON_FIELD then
self:debug('drive now requested, changing to unload course.')
self:releaseUnloader()
self:startUnloadCourse()
else
AIDriver.setDriveNow(self)
end
end
function CombineUnloadAIDriver:getAllTrailersFull()
local fillLevelInfo = {}
AIDriverUtil.getAllFillLevels(self.vehicle, fillLevelInfo, self)
for fillType, info in pairs(fillLevelInfo) do
if self:isValidFillType(fillType) and info.fillLevel < info.capacity then
-- not fuel and not full, so not all full...
-- TODO: this assumes that other than diesel, air, etc. the only fill type we have is the one the
-- combine is harvesting. Could consider the combine's fill type but that sometimes is UNKNOWN
return false
end
end
return true
end
function CombineUnloadAIDriver:shouldDriveOn()
return self:getFillLevelPercent() > self:getDriveOnThreshold()
end
function CombineUnloadAIDriver:getDriveUnloadNow()
return self.settings.driveUnloadNow:get()
end
function CombineUnloadAIDriver:setDriveUnloadNow(driveUnloadNow)
self.settings.driveUnloadNow:set(driveUnloadNow)
self:refreshHUD()
end
function CombineUnloadAIDriver:getCombinesFillLevelPercent()
return g_combineUnloadManager:getCombinesFillLevelPercent(self.combineToUnload)
end
function CombineUnloadAIDriver:getFillLevelThreshold()
return self.vehicle.cp.settings.followAtFillLevel:get()
end
function CombineUnloadAIDriver:getDriveOnThreshold()
return self.vehicle.cp.settings.driveOnAtFillLevel:get()
end
function CombineUnloadAIDriver:onUserUnassignedActiveCombine()
self:debug('User unassigned active combine.')
self:releaseUnloader()
self:setNewOnFieldState(self.states.WAITING_FOR_COMBINE_TO_CALL)
end
function CombineUnloadAIDriver:releaseUnloader()
g_combineUnloadManager:releaseUnloaderFromCombine(self.vehicle, self.combineToUnload)
-- TODO: may not have to release the unloader at this point at all so no need to remember
self.combineJustUnloaded = self.combineToUnload
self.combineToUnload = nil
self:refreshHUD()
end
function CombineUnloadAIDriver:getImFirstOfTwoUnloaders()
return g_combineUnloadManager:getNumUnloaders(self.combineToUnload)==2 and g_combineUnloadManager:getUnloadersNumber(self.vehicle, self.combineToUnload) ==1
end
function CombineUnloadAIDriver:combineIsMakingPocket()
local combineDriver = self.combineToUnload.cp.driver
if combineDriver ~= nil then
return combineDriver.fieldworkUnloadOrRefillState == combineDriver.states.MAKING_POCKET
end
end
-- Make sure the autoAimTargetNode is not moving with the fill level
function CombineUnloadAIDriver:fixAutoAimNode()
self.autoAimNodeFixed = true
end
-- Release the auto aim target to restore default behaviour
function CombineUnloadAIDriver:releaseAutoAimNode()
self.autoAimNodeFixed = false
end
function CombineUnloadAIDriver:isAutoAimNodeFixed()
return self.autoAimNodeFixed
end
-- Make sure the autoAimTargetNode is not moving with the fill level (which adds realism trying to
-- distribute the load more evenly in the trailer but makes life difficult for us)
-- TODO: instead of turning it off completely, could try to reduce the range it is adjusted
function CombineUnloadAIDriver:updateFillUnitAutoAimTarget(superFunc,fillUnit)
local tractor = self.getAttacherVehicle and self:getAttacherVehicle() or nil
if tractor and tractor.cp.driver and tractor.cp.driver.isAutoAimNodeFixed and tractor.cp.driver:isAutoAimNodeFixed() then
local autoAimTarget = fillUnit.autoAimTarget
if autoAimTarget.node ~= nil then
if autoAimTarget.startZ ~= nil and autoAimTarget.endZ ~= nil then
setTranslation(autoAimTarget.node, autoAimTarget.baseTrans[1], autoAimTarget.baseTrans[2], autoAimTarget.startZ)
end
end
else
superFunc(self, fillUnit)
end
end
function CombineUnloadAIDriver:isWithinSafeManeuveringDistance(vehicle)
local d = calcDistanceFrom(self.vehicle.rootNode, AIDriverUtil.getDirectionNode(vehicle))
return d < self.safeManeuveringDistance
end
function CombineUnloadAIDriver:isBehindAndAlignedToChopper(maxDirectionDifferenceDeg)
local dx, _, dz = localToLocal(self.vehicle.rootNode, AIDriverUtil.getDirectionNode(self.combineToUnload), 0, 0, 0)
-- close enough and approximately same direction and behind and not too far to the left or right
return dz < 0 and MathUtil.vector2Length(dx, dz) < 30 and
TurnContext.isSameDirection(AIDriverUtil.getDirectionNode(self.vehicle), AIDriverUtil.getDirectionNode(self.combineToUnload),