-
-
Notifications
You must be signed in to change notification settings - Fork 69
Expand file tree
/
Copy pathAIDriveStrategyCombineCourse.lua
More file actions
2219 lines (2027 loc) · 109 KB
/
AIDriveStrategyCombineCourse.lua
File metadata and controls
2219 lines (2027 loc) · 109 KB
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) 2019-2021 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/>.
]]
---@class AIDriveStrategyCombineCourse : AIDriveStrategyFieldWorkCourse
AIDriveStrategyCombineCourse = CpObject(AIDriveStrategyFieldWorkCourse)
-- fill level when we start making a pocket to unload if we are on the outermost headland
AIDriveStrategyCombineCourse.pocketFillLevelFullPercentage = 95
AIDriveStrategyCombineCourse.safeUnloadDistanceBeforeEndOfRow = 30
-- when fill level is above this threshold, don't start the next row if the pipe would be
-- in the fruit
AIDriveStrategyCombineCourse.waitForUnloadAtEndOfRowFillLevelThreshold = 95
-- When to initiate a self unload before turning to the next row?
-- if the fill level is above this threshold when about to begin a turn and there is a trailer
-- close by, and ...
AIDriveStrategyCombineCourse.selfUnloadBeforeNextRowFillLevelThreshold = 60
-- if the best trailer is less then this (meters) to the left or right
AIDriveStrategyCombineCourse.selfUnloadBeforeNextRowMaxDistance = 50
--- Percentage delta leftover until full, when the combine slows down.
AIDriveStrategyCombineCourse.startingSlowdownFillLevelThreshold = 1.5
--- Minimum working speed, for slowdown.
AIDriveStrategyCombineCourse.normalMinimalWorkingSpeed = 5
AIDriveStrategyCombineCourse.myStates = {
-- main states
UNLOADING_ON_FIELD = {},
-- unload sub-states
STOPPING_FOR_UNLOAD = {},
WAITING_FOR_UNLOAD_ON_FIELD = {},
PULLING_BACK_FOR_UNLOAD = {},
WAITING_FOR_UNLOAD_AFTER_PULLED_BACK = {},
RETURNING_FROM_PULL_BACK = {},
REVERSING_TO_MAKE_A_POCKET = {},
MAKING_POCKET = {},
WAITING_FOR_UNLOAD_IN_POCKET = {},
WAITING_FOR_UNLOAD_BEFORE_STARTING_NEXT_ROW = {},
UNLOADING_BEFORE_STARTING_NEXT_ROW = {},
WAITING_FOR_UNLOAD_AFTER_FIELDWORK_ENDED = {},
WAITING_FOR_UNLOADER_TO_LEAVE = {},
RETURNING_FROM_POCKET = {},
DRIVING_TO_SELF_UNLOAD = {},
DRIVING_TO_SELF_UNLOAD_BEFORE_NEXT_ROW = {}, -- before turning into the next row, we unload into a nearby trailer
SELF_UNLOADING = {},
SELF_UNLOADING_WAITING_FOR_DISCHARGE = {},
DRIVING_TO_SELF_UNLOAD_AFTER_FIELDWORK_ENDED = {},
SELF_UNLOADING_AFTER_FIELDWORK_ENDED = {},
SELF_UNLOADING_AFTER_FIELDWORK_ENDED_WAITING_FOR_DISCHARGE = {},
RETURNING_FROM_SELF_UNLOAD = {},
}
-- stop limit we use for self unload to approach the trailer
AIDriveStrategyCombineCourse.proximityStopThresholdSelfUnload = 0.1
-- 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.
AIDriveStrategyCombineCourse.isAAIDriveStrategyCombineCourse = true
function AIDriveStrategyCombineCourse:init(task, job)
AIDriveStrategyFieldWorkCourse.init(self, task, job)
AIDriveStrategyCourse.initStates(self, AIDriveStrategyCombineCourse.myStates)
--- Combine needs a field polygon for the self-unload to work. Although it is a user setting, but it can be
--- changed during the work, so we always require the field polygon, regardless of the setting, as it is checked
--- only after starting the CP driver.
self.state = self.states.WAITING_FOR_FIELD_BOUNDARY_DETECTION
self.fruitLeft, self.fruitRight = 0, 0
self.litersPerMeter = 0
self.litersPerSecond = 0
self.fillLevelAtLastWaypoint = 0
self.beaconLightsActive = false
self.stopDisabledAfterEmpty = CpTemporaryObject(false)
self.stopDisabledAfterEmpty:set(false, 1)
self:initUnloadStates()
self.chopperCanDischarge = CpTemporaryObject(false)
-- hold the harvester temporarily
self.temporaryHold = CpTemporaryObject(false)
-- periodically check if we need to call an unloader
self.timeToCallUnloader = CpTemporaryObject(true)
self.unloaderRequestedToIgnoreProximity = CpTemporaryObject()
-- we want to keep to pipe open, even if there is no trailer under it
self.forcePipeOpen = CpTemporaryObject()
-- and sometimes, we want to keep it close, even if there is a trailer under it
self.forcePipeClose = CpTemporaryObject()
self.pocketHelperNode = HelperTerrainNode('pocketHelperNode')
--- Register info texts
self:registerInfoTextForStates(self:getFillLevelInfoText(), {
states = {
[self.states.UNLOADING_ON_FIELD] = true
},
unloadStates = {
[self.states.WAITING_FOR_UNLOAD_ON_FIELD] = true,
[self.states.WAITING_FOR_UNLOAD_AFTER_FIELDWORK_ENDED] = true,
[self.states.WAITING_FOR_UNLOAD_AFTER_PULLED_BACK] = true,
[self.states.WAITING_FOR_UNLOAD_IN_POCKET] = true
}
})
end
function AIDriveStrategyCombineCourse:delete()
self.pocketHelperNode:destroy()
AIDriveStrategyFieldWorkCourse.delete(self)
end
function AIDriveStrategyCombineCourse:getStateAsString()
local s = self.state.name
if self.state == self.states.UNLOADING_ON_FIELD then
s = s .. '/' .. self.unloadState.name
end
return s
end
-----------------------------------------------------------------------------------------------------------------------
--- Initialization
-----------------------------------------------------------------------------------------------------------------------
function AIDriveStrategyCombineCourse:setAllStaticParameters()
AIDriveStrategyFieldWorkCourse.setAllStaticParameters(self)
self:debug('AIDriveStrategyCombineCourse set')
if self:isChopper() then
self:debug('This is a chopper.')
end
self:checkMarkers()
self:measureBackDistance()
Markers.setMarkerNodes(self.vehicle, self.measuredBackDistance)
self.proximityController:registerBlockingVehicleListener(self, AIDriveStrategyCombineCourse.onBlockingVehicle)
self.proximityController:registerIgnoreObjectCallback(self, AIDriveStrategyCombineCourse.ignoreProximityObject)
-- distance to keep to the right (>0) or left (<0) when pulling back to make room for the tractor
self.pullBackRightSideOffset = math.abs(self.pipeController:getPipeOffsetX()) - self:getWorkWidth() / 2 + 5
self.pullBackRightSideOffset = self:isPipeOnLeft() and self.pullBackRightSideOffset or -self.pullBackRightSideOffset
-- should be at pullBackRightSideOffset to the right or left at pullBackDistanceStart
self.pullBackDistanceStart = 2 * AIUtil.getTurningRadius(self.vehicle)
-- and back up another bit
self.pullBackDistanceEnd = self.pullBackDistanceStart + 5
-- when making a pocket, how far to back up before changing to forward
-- for very long vehicles, like potato/sugar beet harvesters the 20 meters may not be enough
self.pocketReverseDistance = AIUtil.getVehicleAndImplementsTotalLength(self.vehicle) * 2.2
-- register ourselves at our boss
-- TODO_22 g_combineUnloadManager:addCombineToList(self.vehicle, self)
self.waitingForUnloaderAtEndOfRow = CpTemporaryObject()
--- My unloader. This expires in a few seconds, so unloaders have to renew their registration periodically
---@type CpTemporaryObject
self.unloader = CpTemporaryObject(nil)
--- if this is not nil, we have a pending rendezvous with our unloader
---@type CpTemporaryObject
self.unloaderToRendezvous = CpTemporaryObject(nil)
local total, pipeInFruit = self.vehicle:getFieldWorkCourse():setPipeInFruitMap(self.pipeController:getPipeOffsetX(), self:getWorkWidth())
self:debug('Pipe in fruit map created, there are %d non-headland waypoints, of which at %d the pipe will be in the fruit',
total, pipeInFruit)
self.fillLevelFullPercentage = self.normalFillLevelFullPercentage
end
function AIDriveStrategyCombineCourse:initializeImplementControllers(vehicle)
AIDriveStrategyFieldWorkCourse.initializeImplementControllers(self, vehicle)
local _
self.implementWithPipe, self.pipeController = self:addImplementController(vehicle,
PipeController, Pipe, {}, nil)
self.combineController, self.combine = self:getFirstRegisteredImplementControllerByClass(CombineController)
end
function AIDriveStrategyCombineCourse:getProximitySensorWidth()
-- proximity sensor width across the entire working width
return self:getWorkWidth()
end
-- This part of an ugly workaround to make the chopper pickups work
function AIDriveStrategyCombineCourse:checkMarkers()
for _, implement in pairs(AIUtil.getAllAIImplements(self.vehicle)) do
local aiLeftMarker, aiRightMarker, aiBackMarker = implement.object:getAIMarkers()
if not aiLeftMarker or not aiRightMarker or not aiBackMarker then
self.notAllImplementsHaveAiMarkers = true
return
end
end
end
function AIDriveStrategyCombineCourse:getAllowReversePathfinding()
if self:isTurning() and self:hasAutoAimPipe() and self.unloader:get() ~= nil then
-- chopper with CP unloader turning, disable reverse for pathfinder turns
-- to make following the chopper through the turn easier
return false
else
return AIDriveStrategyFieldWorkCourse.getAllowReversePathfinding(self)
end
end
--- Get the combine object, this can be different from the vehicle in case of tools towed or mounted on a tractor
function AIDriveStrategyCombineCourse:getCombine()
return self.combine
end
function AIDriveStrategyCombineCourse:isAttachedHarvester()
return self.vehicle ~= self.combine
end
function AIDriveStrategyCombineCourse:getPipeOffsetReferenceNode()
if self:isAttachedHarvester() then
-- for attached harvesters this gets the root node of the harvester as that is our reference point to the
-- pipe offsets
return self:getCombine().rootNode
else
return self.vehicle:getAIDirectionNode()
end
end
function AIDriveStrategyCombineCourse:update(dt)
AIDriveStrategyFieldWorkCourse.update(self, dt)
self:updateChopperFillType()
self:onDraw()
end
--- Hold the harvester for a period of periodMs milliseconds
function AIDriveStrategyCombineCourse:hold(periodMs)
if not self.temporaryHold:get() then
self:debug('Temporary hold request for %d milliseconds', periodMs)
end
self.temporaryHold:set(true, math.min(math.max(0, periodMs), 30000))
end
function AIDriveStrategyCombineCourse:getDriveData(dt, vX, vY, vZ)
self:handlePipe(dt)
Markers.refreshMarkerNodes(self.vehicle, self.measuredBackDistance)
if self.temporaryHold:get() then
self:setMaxSpeed(0)
end
if self.state == self.states.INITIAL and self.vehicle:cpGetFieldPolygon() == nil then
self:setMaxSpeed(0)
self.state = self.states.WAITING_FOR_FIELD_BOUNDARY_DETECTION
self:startFieldBoundaryDetection()
end
if self.state == self.states.WAITING_FOR_FIELD_BOUNDARY_DETECTION then
self:setMaxSpeed(0)
if self:waitForFieldBoundary() then
self:debug('Have field boundary now.')
self.state = self.states.INITIAL
end
elseif self.state == self.states.WORKING then
-- Harvesting
self:checkRendezvous()
self:checkBlockingUnloader()
if self:isFull() then
self:changeToUnloadOnField()
elseif self:alwaysNeedsUnloader() then
if not self.pipeController:isFillableTrailerUnderPipe() then
self:debug('Need an unloader to work but have no fillable trailer under the pipe')
self:changeToUnloadOnField()
end
elseif self:shouldWaitAtEndOfRow() then
self:startWaitingForUnloadBeforeNextRow()
end
if not self.pipeController:isInAllowedState() then
self:debugSparse('Pipe is not in allowed state, stop')
self:setMaxSpeed(0)
end
if self:shouldStopForUnloading() then
-- player does not want us to move while discharging
self:setMaxSpeed(0)
else
-- Slowdown the combine near the last few percent, so no crops are leftover,
-- as the combine needs to stop in time, before it's full.
local leftoverPercentage = self.fillLevelFullPercentage - self.combineController:getFillLevelPercentage()
if (leftoverPercentage > 0 and leftoverPercentage < self.startingSlowdownFillLevelThreshold) then
local speed = leftoverPercentage * (self.vehicle:getSpeedLimit(true) / self.startingSlowdownFillLevelThreshold) + self.normalMinimalWorkingSpeed
self:setMaxSpeed(speed)
end
end
elseif self.state == self.states.TURNING then
self:checkBlockingUnloader()
elseif self.state == self.states.WAITING_FOR_LOWER then
if self:isFull() then
self:debug('Waiting for lower but full...')
self:changeToUnloadOnField()
end
elseif self.state == self.states.UNLOADING_ON_FIELD then
-- Unloading
self:driveUnloadOnField()
if self:isWaitingForUnload() then
self:callUnloaderWhenNeeded()
end
end
if self:isTurning() and not self:isFinishingRow() then
if self:shouldHoldInTurnManeuver() then
self:setMaxSpeed(0)
end
end
return AIDriveStrategyFieldWorkCourse.getDriveData(self, dt, vX, vY, vZ)
end
function AIDriveStrategyCombineCourse:updateFieldworkOffset(course)
if self.state == self.states.UNLOADING_ON_FIELD and self:isUnloadStateOneOf(self.selfUnloadStates) then
-- do not apply fieldwork offset when not doing fieldwork
course:setOffset((self.aiOffsetX or 0) + (self.tightTurnOffset or 0), (self.aiOffsetZ or 0))
else
course:setOffset(self.settings.toolOffsetX:getValue() + (self.aiOffsetX or 0) + (self.tightTurnOffset or 0),
(self.aiOffsetZ or 0))
end
end
function AIDriveStrategyCombineCourse:checkDistanceToOtherFieldWorkers()
-- do not slow down/stop for convoy while unloading
if self.state ~= self.states.UNLOADING_ON_FIELD then
self:setMaxSpeed(self.fieldWorkerProximityController:getMaxSpeed(self.settings.convoyDistance:getValue(), self.maxSpeed))
end
end
--- Take care of unloading on the field. This could be stopping and waiting for an unloader or
--- self unloading.
--- The output of this function is:
--- * set self.maxSpeed
--- * change the course to run, for example pulling back/making pocket or self unload
--- * this does not supply drive target point
function AIDriveStrategyCombineCourse:driveUnloadOnField()
if self.unloadState == self.states.STOPPING_FOR_UNLOAD then
self:setMaxSpeed(0)
-- wait until we stopped before raising the implements
if AIUtil.isStopped(self.vehicle) then
if self.raiseHeaderAfterStopped then
self:debug('Stopped, now raise implements and switch to next unload state')
self:raiseImplements()
end
self.unloadState = self.newUnloadStateAfterStopped
end
elseif self.unloadState == self.states.PULLING_BACK_FOR_UNLOAD then
self:setMaxSpeed(self.settings.reverseSpeed:getValue())
elseif self.unloadState == self.states.REVERSING_TO_MAKE_A_POCKET then
self:setMaxSpeed(self.settings.reverseSpeed:getValue())
elseif self.unloadState == self.states.MAKING_POCKET then
self:setMaxSpeed(self.settings.fieldWorkSpeed:getValue())
local _, _, dz = self.pocketHelperNode:localToLocal(self.vehicle:getAIDirectionNode(), 0, 0,
self.pipeController:getPipeOffsetZ())
if dz > -18 then
-- we are close enough to the reference waypoint, so stop making the pocket and wait for unload.
self:debug('Waiting for unload in the pocket')
self.unloadState = self.states.WAITING_FOR_UNLOAD_IN_POCKET
end
elseif self.unloadState == self.states.RETURNING_FROM_PULL_BACK then
self:setMaxSpeed(self.settings.turnSpeed:getValue())
elseif self.unloadState == self.states.WAITING_FOR_UNLOAD_IN_POCKET or
self.unloadState == self.states.WAITING_FOR_UNLOAD_AFTER_PULLED_BACK or
self.unloadState == self.states.UNLOADING_BEFORE_STARTING_NEXT_ROW then
if self:isUnloadFinished() then
-- reset offset to return to the original up/down row after we unloaded in the pocket
self.aiOffsetX = 0
-- wait a bit after the unload finished to give a chance to the unloader to move away
self.stateBeforeWaitingForUnloaderToLeave = self.unloadState
self.unloadState = self.states.WAITING_FOR_UNLOADER_TO_LEAVE
self.waitingForUnloaderSince = g_currentMission.time
self:debug('Unloading finished, wait for the unloader to leave...')
else
self:setMaxSpeed(0)
end
elseif self.unloadState == self.states.WAITING_FOR_UNLOAD_ON_FIELD then
if g_updateLoopIndex % 5 == 0 then
--small delay, to make sure no more fillLevel change is happening
if not self:isFull() and not self:shouldStopForUnloading() and not self:alwaysNeedsUnloader() then
self:debug('not full anymore, can continue working')
self:changeToFieldWork()
elseif self:alwaysNeedsUnloader() and self:isFillableTrailerUnderPipe() then
self:debug('Need an unloader to work, now have a trailer under the pipe, can continue working')
self:changeToFieldWork()
end
end
self:setMaxSpeed(0)
elseif self.unloadState == self.states.WAITING_FOR_UNLOAD_BEFORE_STARTING_NEXT_ROW then
self:setMaxSpeed(0)
if self:isDischarging() then
self:cancelRendezvous()
self.unloadState = self.states.UNLOADING_BEFORE_STARTING_NEXT_ROW
self:debug('Unloading started at end of row')
end
if not self.waitingForUnloaderAtEndOfRow:get() then
local unloaderWhoDidNotShowUp = self.unloaderToRendezvous:get()
self:cancelRendezvous()
if unloaderWhoDidNotShowUp then
unloaderWhoDidNotShowUp:getCpDriveStrategy():onMissedRendezvous(self)
end
self:debug('Waited for unloader at the end of the row but it did not show up, try to continue')
self:changeToFieldWork()
end
elseif self.unloadState == self.states.WAITING_FOR_UNLOAD_AFTER_FIELDWORK_ENDED then
local fillLevel = self.combineController:getFillLevel()
if fillLevel < 0.01 then
self:debug('Unloading finished after fieldwork ended, end course')
AIDriveStrategyFieldWorkCourse.finishFieldWork(self)
else
self:setMaxSpeed(0)
end
elseif self.unloadState == self.states.WAITING_FOR_UNLOADER_TO_LEAVE then
self:setMaxSpeed(0)
-- TODO: instead of just wait a few seconds we could check if the unloader has actually left
if self.waitingForUnloaderSince + 5000 < g_currentMission.time then
if self.stateBeforeWaitingForUnloaderToLeave == self.states.WAITING_FOR_UNLOAD_AFTER_PULLED_BACK then
local pullBackReturnCourse = self.pathfinderController:findAnalyticPathFromVehicleToGoal(
self.positionToContinueAfterPullback, self:getAllowReversePathfinding())
if pullBackReturnCourse then
self.unloadState = self.states.RETURNING_FROM_PULL_BACK
self:debug('Unloading finished, returning to fieldwork on return course')
self.ppc:setShortLookaheadDistance()
self:startCourse(pullBackReturnCourse, 1)
self:rememberCourse(self.courseAfterPullBack, self.ixAfterPullBack)
else
self:debug('Unloading finished, returning to fieldwork directly')
self:startCourse(self.courseAfterPullBack, self.ixAfterPullBack)
self.ppc:setNormalLookaheadDistance()
self:changeToFieldWork()
end
elseif self.stateBeforeWaitingForUnloaderToLeave == self.states.WAITING_FOR_UNLOAD_IN_POCKET then
self:debug('Unloading in pocket finished, returning to fieldwork')
self.fillLevelFullPercentage = self.normalFillLevelFullPercentage
self:changeToFieldWork()
elseif self.stateBeforeWaitingForUnloaderToLeave == self.states.UNLOADING_BEFORE_STARTING_NEXT_ROW then
self:debug('Unloading before next row finished, returning to fieldwork')
self:changeToFieldWork()
elseif self.stateBeforeWaitingForUnloaderToLeave == self.states.WAITING_FOR_UNLOAD_ON_FIELD then
self:debug('Unloading on field finished, returning to fieldwork')
self:changeToFieldWork()
else
self:debug('Unloading finished, previous state not known, returning to fieldwork')
self:changeToFieldWork()
end
end
elseif self:isUnloadStateOneOf(self.drivingToSelfUnloadStates) then
if self:isCloseToCourseEnd(25) then
-- slow down towards the end of the course, near the trailer
self:setMaxSpeed(math.min(10, 0.5 * self.settings.fieldSpeed:getValue()))
-- we'll be very close to the tractor/trailer, don't stop too soon
self.proximityController:setTemporaryStopThreshold(self.proximityStopThresholdSelfUnload, 3000)
if g_vehicleConfigurations:getRecursively(self.vehicle, 'openPipeEarly') then
if not self.pipeController:isPipeOpen() then
self:debug('Opening pipe early to not crash it into the trailer')
self.pipeController:openPipe()
end
self.forcePipeOpen:set(true, 1000)
end
else
self:setMaxSpeed(self.settings.fieldSpeed:getValue())
end
elseif self.unloadState == self.states.SELF_UNLOADING_WAITING_FOR_DISCHARGE then
self:setMaxSpeed(0)
self:debugSparse('Waiting for the self unloading to start')
if self:isDischarging() then
self.unloadState = self.states.SELF_UNLOADING
end
elseif self.unloadState == self.states.SELF_UNLOADING then
self:setMaxSpeed(0)
if self:isUnloadFinished() then
if not self:continueSelfUnloadToNextTrailer() then
self:debug('Self unloading finished, returning to fieldwork')
self:returnToFieldworkAfterSelfUnload()
end
end
elseif self.unloadState == self.states.SELF_UNLOADING_AFTER_FIELDWORK_ENDED_WAITING_FOR_DISCHARGE then
self:setMaxSpeed(0)
self:debugSparse('Fieldwork ended, waiting for the self unloading to start')
if self:isDischarging() then
self.unloadState = self.states.SELF_UNLOADING_AFTER_FIELDWORK_ENDED
end
elseif self.unloadState == self.states.SELF_UNLOADING_AFTER_FIELDWORK_ENDED then
self:setMaxSpeed(0)
if self:isUnloadFinished() then
if not self:continueSelfUnloadToNextTrailer() then
self:debug('Self unloading finished after fieldwork ended, finishing fieldwork')
AIDriveStrategyFieldWorkCourse.finishFieldWork(self)
end
end
elseif self.unloadState == self.states.RETURNING_FROM_SELF_UNLOAD then
if self:isCloseToCourseStart(25) then
self:setMaxSpeed(0.5 * self.settings.fieldSpeed:getValue())
-- we'll be very close to the tractor/trailer, don't stop too soon
self.proximityController:setTemporaryStopThreshold(self.proximityStopThresholdSelfUnload, 3000)
else
self:setMaxSpeed(self.settings.fieldSpeed:getValue())
end
-- apply the work starter's speed limit (when approaching the work start)
local _, _, _, maxSpeed = self.workStarter:getDriveData()
if maxSpeed ~= nil then
self:setMaxSpeed(maxSpeed)
end
end
end
-----------------------------------------------------------------------------------------------------------------------
--- Event listeners
-----------------------------------------------------------------------------------------------------------------------
function AIDriveStrategyCombineCourse:onWaypointPassed(ix, course)
if self.state == self.states.UNLOADING_ON_FIELD and
(self.unloadState == self.states.DRIVING_TO_SELF_UNLOAD or
self.unloadState == self.states.DRIVING_TO_SELF_UNLOAD_BEFORE_NEXT_ROW or
self.unloadState == self.states.DRIVING_TO_SELF_UNLOAD_AFTER_FIELDWORK_ENDED or
self.unloadState == self.states.RETURNING_FROM_SELF_UNLOAD) then
-- nothing to do while driving to unload and back
return AIDriveStrategyFieldWorkCourse.onWaypointPassed(self, ix, course)
end
self:checkFruit()
-- make sure we start making a pocket while we still have some fill capacity left as we'll be
-- harvesting fruit while making the pocket unless we have self unload turned on
if self:shouldMakePocket() and not self.settings.selfUnload:getValue() then
self.fillLevelFullPercentage = self.pocketFillLevelFullPercentage
end
local isOnHeadland = self.course:isOnHeadland(ix)
self.combineController:updateStrawSwath(isOnHeadland)
if self.state == self.states.WORKING then
if not self:alwaysNeedsUnloader() then
self:estimateDistanceUntilFull(ix)
self:callUnloaderWhenNeeded()
end
end
if self.returnedFromPocketIx and self.returnedFromPocketIx == ix then
-- back to normal look ahead distance for PPC, no tight turns are needed anymore
self:debug('Reset PPC to normal lookahead distance')
self.ppc:setNormalLookaheadDistance()
end
AIDriveStrategyFieldWorkCourse.onWaypointPassed(self, ix, course)
end
--- Called when the last waypoint of a course is passed
function AIDriveStrategyCombineCourse:onLastWaypointPassed()
local fillLevel = self.combineController:getFillLevel()
if self.state == self.states.UNLOADING_ON_FIELD then
if self.unloadState == self.states.RETURNING_FROM_PULL_BACK then
self:debug('Pull back finished, returning to fieldwork')
self.ppc:setNormalLookaheadDistance()
self:startRememberedCourse()
self:changeToFieldWork()
elseif self.unloadState == self.states.RETURNING_FROM_SELF_UNLOAD then
self:debug('Back from self unload, returning to fieldwork')
self.workStarter:onLastWaypoint()
elseif self.unloadState == self.states.REVERSING_TO_MAKE_A_POCKET then
self:debug('Reversed, now start making a pocket')
self:lowerImplements()
self.state = self.states.UNLOADING_ON_FIELD
self.unloadState = self.states.MAKING_POCKET
-- offset the main fieldwork course and start on it
self.aiOffsetX = math.min(self.pullBackRightSideOffset, self:getWorkWidth())
self:startRememberedCourse()
elseif self.unloadState == self.states.PULLING_BACK_FOR_UNLOAD then
-- pulled back, now wait for unload
self.unloadState = self.states.WAITING_FOR_UNLOAD_AFTER_PULLED_BACK
self:debug('Pulled back, now wait for unload')
elseif self.unloadState == self.states.DRIVING_TO_SELF_UNLOAD or
self.unloadState == self.states.DRIVING_TO_SELF_UNLOAD_BEFORE_NEXT_ROW then
self:debug('Self unloading point reached, fill level %.1f, waiting for unload to start.', fillLevel)
self.unloadState = self.states.SELF_UNLOADING_WAITING_FOR_DISCHARGE
elseif self.unloadState == self.states.DRIVING_TO_SELF_UNLOAD_AFTER_FIELDWORK_ENDED then
self:debug('Self unloading point reached after fieldwork ended, fill level %.1f, waiting for unload to start.', fillLevel)
self.unloadState = self.states.SELF_UNLOADING_AFTER_FIELDWORK_ENDED_WAITING_FOR_DISCHARGE
end
elseif self.state == self.states.WORKING and fillLevel > 0 then
-- reset offset we used for the course ending to not miss anything
self.aiOffsetZ = 0
if self.settings.selfUnload:getValue() and
self:startSelfUnload(self.states.DRIVING_TO_SELF_UNLOAD_AFTER_FIELDWORK_ENDED) then
self:debug('Start self unload after fieldwork ended')
else
-- let AutoDrive know we are done and can unload
self:debug('Fieldwork done, fill level is %.1f, now waiting to be unloaded.', fillLevel)
self.state = self.states.UNLOADING_ON_FIELD
self.unloadState = self.states.WAITING_FOR_UNLOAD_AFTER_FIELDWORK_ENDED
end
else
AIDriveStrategyFieldWorkCourse.onLastWaypointPassed(self)
end
end
-----------------------------------------------------------------------------------------------------------------------
--- State changes
-----------------------------------------------------------------------------------------------------------------------
--- Some of our turns need a short look ahead distance, make sure we restore the normal after the turn
function AIDriveStrategyCombineCourse:resumeFieldworkAfterTurn(ix)
self.ppc:setNormalLookaheadDistance()
AIDriveStrategyFieldWorkCourse.resumeFieldworkAfterTurn(self, ix)
end
--- Stop, raise the header (if needed) and then, and only then change to the new states. This is to avoid leaving
--- unharvested spots due to the header being lifted while the vehicle is still in motion.
function AIDriveStrategyCombineCourse:stopForUnload(newUnloadStateAfterStopped, raiseHeaderAfterStopped)
self.state = self.states.UNLOADING_ON_FIELD
self.unloadState = self.states.STOPPING_FOR_UNLOAD
self.newUnloadStateAfterStopped = newUnloadStateAfterStopped
self.raiseHeaderAfterStopped = raiseHeaderAfterStopped
end
--- Start waiting for the implements to lower
-- getCanAIVehicleContinueWork() seems to return false when the implement being lowered/raised (moving) but
-- true otherwise. Due to some timing issues it may return true just after we started lowering it
-- so the harvester misses some fruit when restarting after unloading ended
function AIDriveStrategyCombineCourse:startWaitingForLower()
-- force delayed lower
self.state = self.states.WAITING_FOR_LOWER_DELAYED
self:debug('waiting for lower delayed')
end
function AIDriveStrategyCombineCourse:changeToUnloadOnField()
self:checkFruit()
-- TODO: check around turn maneuvers we may not want to pull back before a turn
self:rememberCourse(self.fieldWorkCourse, self:getBestWaypointToContinueFieldWork())
if self.settings.selfUnload:getValue() and self:startSelfUnload(self.states.DRIVING_TO_SELF_UNLOAD) then
self:debug('Start self unload')
elseif self.settings.avoidFruit:getValue() and self:shouldMakePocket() then
-- I'm on the edge of the field or fruit is on both sides, make a pocket on the right side and wait there for the unload
local pocketCourse, nextIx = self:createPocketCourse()
if pocketCourse then
self:debug('No room to the left, making a pocket for unload')
self.state = self.states.UNLOADING_ON_FIELD
self.unloadState = self.states.REVERSING_TO_MAKE_A_POCKET
-- place a marker at the current pipe position, we'll use this to find out where to stop
-- making the pocket
self.pocketHelperNode:placeAtNode(Markers.getFrontMarkerNode(self.vehicle), 1, 0, 0, 0)
self:rememberCourse(self.course, nextIx)
-- raise header for reversing
self:raiseImplements()
self:startCourse(pocketCourse, 1)
-- tighter turns
self.ppc:setShortLookaheadDistance()
else
self:startWaitingForUnloadWhenFull()
end
elseif self.settings.avoidFruit:getValue() and self:shouldPullBack() then
-- is our pipe in the fruit? (assuming pipe is on the left side)
local pullBackCourse = self:createPullBackCourse()
if pullBackCourse then
self:debug('Pipe in fruit, pulling back to make room for unloading')
self:stopForUnload(self.states.PULLING_BACK_FOR_UNLOAD, true)
self.courseAfterPullBack = self.course
self.ixAfterPullBack = self.ppc:getLastPassedWaypointIx() or self.ppc:getCurrentWaypointIx()
-- remember where to start after the pull back, a bit further back just in case.
self.positionToContinueAfterPullback = PathfinderUtil.getVehiclePositionAsState3D(self.vehicle, 0, -2)
-- tighter turns
self.ppc:setShortLookaheadDistance()
self:startCourse(pullBackCourse, 1)
else
self:startWaitingForUnloadWhenFull()
end
else
self:startWaitingForUnloadWhenFull()
end
end
function AIDriveStrategyCombineCourse:startWaitingForUnloadWhenFull()
self:stopForUnload(self.states.WAITING_FOR_UNLOAD_ON_FIELD, true)
self:debug('Waiting for the unloader on the field')
g_currentMission:addIngameNotification(FSBaseMission.INGAME_NOTIFICATION_CRITICAL,
string.format(g_i18n:getText("ai_messageErrorGrainTankIsFull"), self.vehicle:getCurrentHelper().name))
end
function AIDriveStrategyCombineCourse:startWaitingForUnloadBeforeNextRow()
self:debug('Waiting for unload before starting the next row')
self.waitingForUnloaderAtEndOfRow:set(true, 30000)
self:stopForUnload(self.states.WAITING_FOR_UNLOAD_BEFORE_STARTING_NEXT_ROW, true)
end
--- The unloader may call this repeatedly to confirm that the rendezvous still stands, making sure the
--- combine won't give up and keeps waiting
function AIDriveStrategyCombineCourse:reconfirmRendezvous()
if self.waitingForUnloaderAtEndOfRow:get() then
-- ok, we'll wait another 30 seconds
self.waitingForUnloaderAtEndOfRow:set(true, 30000)
end
end
function AIDriveStrategyCombineCourse:isUnloadFinished()
local fillLevel = self.combineController:getFillLevel()
-- unload is done when fill levels are ok (not full) and not discharging anymore (either because we
-- are empty or the trailer is full)
return (not self:isFull() and self.pipeController:justStoppedDischarging()) or fillLevel < 0.1
end
function AIDriveStrategyCombineCourse:isFull(fillLevelFullPercentage)
local fillLevelPercentage = self.combineController:getFillLevelPercentage()
if fillLevelPercentage >= 100 or fillLevelPercentage > (fillLevelFullPercentage or self.fillLevelFullPercentage) then
self:debugSparse('Full or refillUntilPct reached: %.2f', fillLevelPercentage)
return true
end
if fillLevelPercentage < 0.1 then
self.stopDisabledAfterEmpty:set(true, 2000)
end
return false
end
function AIDriveStrategyCombineCourse:shouldMakePocket()
if self:alwaysNeedsUnloader() then
self:debug('Always need unloader so not making a pocket')
return false
end
-- fruitLeft/fruitRight are percentage of fruit covered area. Also, sugarbeet and some other fruits
-- return 50% even after harvested, so check for 75% to be on the safe side
if self.fruitLeft > 75 and self.fruitRight > 75 then
-- fruit both sides
return true
elseif self:isPipeOnLeft() then
-- on the outermost headland clockwise (field edge)
return not self.fieldOnLeft
else
-- on the outermost headland counterclockwise (field edge)
return not self.fieldOnRight
end
end
function AIDriveStrategyCombineCourse:shouldPullBack()
if self:alwaysNeedsUnloader() then
self:debug('Always need unloader so not making a pocket')
return false
else
return self:isPipeInFruit()
end
end
function AIDriveStrategyCombineCourse:isPipeOnLeft()
return self.pipeController:isPipeOnTheLeftSide()
end
function AIDriveStrategyCombineCourse:isPipeInFruit()
-- is our pipe in the fruit?
if self:isPipeOnLeft() then
return self.fruitLeft > self.fruitRight
else
return self.fruitLeft < self.fruitRight
end
end
---@return number, number the amount of fruit on left/right side of the combine. 0 is no fruit, and it is probably
--- a number up to 100, indicating how much fruit is there.
function AIDriveStrategyCombineCourse:getFruitAtSides()
return self.fruitLeft, self.fruitRight
end
--- Check both sides of the combine/chopper to see if we are at the edge of the field and if there is fruit there.
--- This is to direct the unloader to the side where there is no fruit.
function AIDriveStrategyCombineCourse:checkFruit()
local workWidth = self:getWorkWidth()
local x, _, z = localToWorld(self.vehicle:getAIDirectionNode(), workWidth, 0, 0)
self.fieldOnLeft = CpFieldUtil.isOnField(x, z)
_, self.fruitLeft = PathfinderUtil.hasFruit(x, z, 1, 1)
self.fruitLeft = self.fruitLeft or 0
x, _, z = localToWorld(self.vehicle:getAIDirectionNode(), -workWidth, 0, 0)
self.fieldOnRight = CpFieldUtil.isOnField(x, z)
_, self.fruitRight = PathfinderUtil.hasFruit(x, z, 1, 1)
self.fruitRight = self.fruitRight or 0
self:debug('Fruit left: %.2f right %.2f, field on left %s, right %s',
self.fruitLeft, self.fruitRight, tostring(self.fieldOnLeft), tostring(self.fieldOnRight))
end
--- Estimate the waypoint where the combine will be full/reach the fill level where it should start unloading
--- (waypointIxWhenFull/waypointIxWhenCallUnloader), based on the current harvest rate
function AIDriveStrategyCombineCourse:estimateDistanceUntilFull(ix)
-- calculate fill rate so the combine driver knows if it can make the next row without unloading
local fillLevel = self.combineController:getFillLevel()
local capacity = self.combineController:getCapacity()
if ix > 1 then
local dToNext = self.course:getDistanceToNextWaypoint(ix - 1)
if self.fillLevelAtLastWaypoint and self.fillLevelAtLastWaypoint > 0 and self.fillLevelAtLastWaypoint <= fillLevel then
local litersPerMeter
if dToNext > 0.1 then
litersPerMeter = (fillLevel - self.fillLevelAtLastWaypoint) / dToNext
else
-- use the last known liters per meter if the distance is too short
litersPerMeter = self.litersPerMeter
end
local litersPerSecond = 0
if self.fillLevelLastCheckedTime and (self.fillLevelLastCheckedTime < g_currentMission.time) then
litersPerSecond = (fillLevel - self.fillLevelAtLastWaypoint) /
((g_currentMission.time - self.fillLevelLastCheckedTime) / 1000)
end
-- smooth everything a bit, also ignore 0
self.litersPerMeter = litersPerMeter > 0 and ((self.litersPerMeter + litersPerMeter) / 2) or self.litersPerMeter
self.litersPerSecond = litersPerSecond > 0 and ((self.litersPerSecond + litersPerSecond) / 2) or self.litersPerSecond
else
-- no history yet, so make sure we don't end up with some unrealistic numbers
self.waypointIxWhenFull = nil
self.litersPerMeter = 0
self.litersPerSecond = 0
end
self:debug('Fill rate is %.1f l/m, %.1f l/s (fill level %.1f of %.1f, last %.1f, dToNext = %.1f)',
self.litersPerMeter, self.litersPerSecond, fillLevel, capacity, self.fillLevelAtLastWaypoint, dToNext)
self.fillLevelLastCheckedTime = g_currentMission.time
self.fillLevelAtLastWaypoint = fillLevel
end
local litersUntilFull = capacity - fillLevel
local dUntilFull = CpMathUtil.divide(litersUntilFull, self.litersPerMeter)
local litersUntilCallUnloader = capacity * self.settings.callUnloaderPercent:getValue() / 100 - fillLevel
local dUntilCallUnloader = CpMathUtil.divide(litersUntilCallUnloader, self.litersPerMeter)
self.waypointIxWhenFull = self.course:getNextWaypointIxWithinDistance(ix, dUntilFull) or self.course:getNumberOfWaypoints()
local wpDistance
self.waypointIxWhenCallUnloader, wpDistance = self.course:getNextWaypointIxWithinDistance(ix, dUntilCallUnloader)
self:debug('Will be full at waypoint %d, fill level %d at waypoint %d (current waypoint %d), %.1f m and %.1f l until call (currently %.1f l), wp distance %.1f',
self.waypointIxWhenFull or -1, self.settings.callUnloaderPercent:getValue(), self.waypointIxWhenCallUnloader or -1,
self.course:getCurrentWaypointIx(), dUntilCallUnloader, litersUntilCallUnloader, fillLevel, wpDistance)
end
function AIDriveStrategyCombineCourse:shouldWaitAtEndOfRow()
if self.settings.selfUnload:getValue() then
-- don't wait for anyone when self unloading
return false
end
local nextRowStartIx = self.course:getNextRowStartIx(self.ppc:getRelevantWaypointIx())
local lastPassedWaypointIx = self.ppc:getLastPassedWaypointIx() or self.ppc:getRelevantWaypointIx()
local distanceToNextTurn = self.course:getDistanceToNextTurn(lastPassedWaypointIx) or math.huge
local closeToTurn = distanceToNextTurn < AIDriveStrategyCombineCourse.safeUnloadDistanceBeforeEndOfRow
-- If close to the end of the row and the pipe would be in the fruit after the turn, and our fill level is high,
-- we always wait here for an unloader, regardless of having a rendezvous or not (unless we have our pipe in fruit here)
if nextRowStartIx and closeToTurn and
self:isPipeInFruitAt(nextRowStartIx) and
self:isFull(AIDriveStrategyCombineCourse.waitForUnloadAtEndOfRowFillLevelThreshold) then
self:checkFruit()
if not self:isPipeInFruit() then
self:debug('shouldWaitAtEndOfRow: Closer than %.1f m to a turn, pipe would be in fruit after turn at %d, fill level over %.1f',
AIDriveStrategyCombineCourse.safeUnloadDistanceBeforeEndOfRow, nextRowStartIx,
AIDriveStrategyCombineCourse.waitForUnloadAtEndOfRowFillLevelThreshold)
return true
end
end
-- Or, if we are close to the turn and have a rendezvous waypoint before the turn
if nextRowStartIx and closeToTurn and
self.unloaderRendezvousWaypointIx and
nextRowStartIx > self.unloaderRendezvousWaypointIx then
self:debug('shouldWaitAtEndOfRow: Closer than %.1f m to a turn and rendezvous waypoint %d is before the turn, waiting for the unloader here',
AIDriveStrategyCombineCourse.safeUnloadDistanceBeforeEndOfRow, self.unloaderRendezvousWaypointIx)
return true
end
end
------------------------------------------------------------------------------------------------------------------------
--- Unloader handling
---
--- We need to answer the following questions:
--- 1. When to call the unloader?
--- 2. Where to meet the unloader?
--- 3. Which unloader to call?
---
--- To question #3, we check the distance between the unloader and the target (combine and a rendezvous point) and based
--- on the unloader's distance to the target and its fill level, we calculate a score and call the unloader with
--- the best score.
---
--- To questions #1 and #2, we have to cases:
---
--- The easy case
---
--- If the combine is stopped for unloading (either 100% full, or made a pocket or finished the course, etc.),
--- the unloader must drive to the combine immediately.
---
--- The difficult case
---
--- The combine is still harvesting, and periodically calculates the waypoint/distance where it will reach the fill
--- level threshold configured. This is the fill level when we want the unload process to start, so the unloader
--- is supposed to meet the combine at that (rendezvous) spot. This answers #2, where to meet the unloader.
--- But when to call the unloader? When it will reach the rendezvous point about the same time (or a little earlier)
--- as the combine reaches it. So we ask around all unloaders to figure out what their estimated time en-route (ETE)
--- to the rendezvous waypoint would be. Then pick the one with the shortest ETE, and if its ETE (plus some reserve)
--- is more than the combine's ETE, call it.
---
------------------------------------------------------------------------------------------------------------------------
function AIDriveStrategyCombineCourse:callUnloaderWhenNeeded()
if not self.timeToCallUnloader:get() then
return
end
-- check back again in a few seconds
self.timeToCallUnloader:set(false, 3000)
if self.unloader:get() then
self:debug('callUnloaderWhenNeeded: already has an unloader assigned (%s)', CpUtil.getName(self.unloader:get()))
return
end
local bestUnloader, bestEte
if self:isWaitingForUnload() then
self:debug('callUnloaderWhenNeeded: stopped, need unloader here')
bestUnloader, _ = self:findUnloader(self.vehicle, nil)
if bestUnloader then
bestUnloader:getCpDriveStrategy():call(self.vehicle, nil)
end
else
if not self.waypointIxWhenCallUnloader then
self:debug('callUnloaderWhenNeeded: don\'t know yet where to meet the unloader')
return
end
-- Find a good waypoint to unload, as the calculated one may have issues, like pipe would be in the fruit,
-- or in a turn, etc.
-- TODO: isPipeInFruitAllowed
local tentativeRendezvousWaypointIx = self:findBestWaypointToUnload(self.waypointIxWhenCallUnloader, false)
if not tentativeRendezvousWaypointIx then
self:debug('callUnloaderWhenNeeded: can\'t find a good waypoint to meet the unloader')
return
end
bestUnloader, bestEte = self:findUnloader(nil, self.course:getWaypoint(tentativeRendezvousWaypointIx))
-- getSpeedLimit() may return math.huge (inf), when turning for example, not sure why, and that throws off
-- our ETE calculation
if bestUnloader and self.vehicle:getSpeedLimit(true) < 100 then
local dToUnloadWaypoint = self.course:getDistanceBetweenWaypoints(tentativeRendezvousWaypointIx,
self.course:getCurrentWaypointIx())
local myEte = dToUnloadWaypoint / (self.vehicle:getSpeedLimit(true) / 3.6)
self:debug('callUnloaderWhenNeeded: best unloader ETE at waypoint %d %.1fs, my ETE %.1fs',
tentativeRendezvousWaypointIx, bestEte, myEte)
if bestEte - 5 > myEte then
-- I'll be at the rendezvous a lot earlier than the unloader which will almost certainly result in the
-- cancellation of the rendezvous.
-- So, set something up further away, with better chances,
-- using the unloader's ETE, knowing that 1) that ETE is for the current rendezvous point, 2) there
-- may be another unloader selected for that waypoint
local dToTentativeRendezvousWaypoint = bestEte * (self.vehicle:getSpeedLimit(true) / 3.6)
self:debug('callUnloaderWhenNeeded: too close to rendezvous waypoint, trying move it %.1fm',
dToTentativeRendezvousWaypoint)
tentativeRendezvousWaypointIx = self.course:getNextWaypointIxWithinDistance(
self.course:getCurrentWaypointIx(), dToTentativeRendezvousWaypoint)
if tentativeRendezvousWaypointIx then
bestUnloader, bestEte = self:findUnloader(nil, self.course:getWaypoint(tentativeRendezvousWaypointIx))
if bestUnloader then
self:callUnloader(bestUnloader, tentativeRendezvousWaypointIx, bestEte)
end
else
self:debug('callUnloaderWhenNeeded: still can\'t find a good waypoint to meet the unloader')
end
elseif bestEte + 5 > myEte then
-- do not call too early (like minutes before we get there), only when it needs at least as
-- much time to get there as the combine (-5 seconds)
self:callUnloader(bestUnloader, tentativeRendezvousWaypointIx, bestEte)
end
end
end
end
function AIDriveStrategyCombineCourse:callUnloader(bestUnloader, tentativeRendezvousWaypointIx, bestEte)
if bestUnloader:getCpDriveStrategy():call(self.vehicle,
self.course:getWaypoint(tentativeRendezvousWaypointIx)) then
self.unloaderToRendezvous:set(bestUnloader, 1000 * (bestEte + 30))
self.unloaderRendezvousWaypointIx = tentativeRendezvousWaypointIx
self:debug('callUnloaderWhenNeeded: harvesting, unloader accepted rendezvous at waypoint %d', self.unloaderRendezvousWaypointIx)
else
self:debug('callUnloaderWhenNeeded: harvesting, unloader rejected rendezvous at waypoint %d', tentativeRendezvousWaypointIx)
end
end
---@param vehicle table
---@return boolean true if vehicle is an active Courseplay controlled combine/harvester
function AIDriveStrategyCombineCourse.isActiveCpCombine(vehicle)
if not (vehicle.getIsCpActive and vehicle:getIsCpActive()) then
-- not driven by CP
return false
end
local driveStrategy = vehicle.getCpDriveStrategy and vehicle:getCpDriveStrategy()
return driveStrategy and driveStrategy.callUnloader ~= nil
end
--- Find an unloader to drive to the target, which may either be the combine itself (when stopped and waiting for unload)
--- or a waypoint which the combine will reach in the future. Combine and waypoint parameters are mutually exclusive.
---@param combine table the combine vehicle if we need the unloader come to the combine, otherwise nil
---@param waypoint Waypoint the waypoint where the unloader should meet the combine, otherwise nil.
---@return table, number the best fitting unloader or nil, the estimated time en-route for the unloader to reach the
--- target (combine or waypoint)
function AIDriveStrategyCombineCourse:findUnloader(combine, waypoint)
local bestScore = -math.huge
local bestUnloader, bestEte
for _, vehicle in pairs(g_currentMission.vehicleSystem.vehicles) do
if AIDriveStrategyUnloadCombine.isActiveCpCombineUnloader(vehicle) then
local x, _, z = getWorldTranslation(self.vehicle.rootNode)
---@type AIDriveStrategyUnloadCombine
local driveStrategy = vehicle:getCpDriveStrategy()
-- look a bit outside of the field as the harvester's root node may be just off the field (like in a turn,
-- or when starting.
if driveStrategy:isServingPosition(x, z, 10) then
local unloaderFillLevelPercentage = driveStrategy:getFillLevelPercentage()
if driveStrategy:isAllowedToBeCalled() and unloaderFillLevelPercentage < 99 then
local unloaderDistance, unloaderEte
if combine then
-- if already stopped, we want the unloader to come to us