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 527
/
Waypoint.lua
1789 lines (1611 loc) · 64.7 KB
/
Waypoint.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) 2018 Peter Vajko
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 Point
Point = CpObject()
function Point:init(x, z, yRotation)
self.x = x
self.z = z
self.yRotation = yRotation or 0
end
function Point:clone()
return Point(self.x, self.z, self.yRotation)
end
---@param other Point
function Point:copy(other)
return self:clone(other)
end
function Point:translate(dx, dz)
self.x = self.x + dx
self.z = self.z + dz
end
function Point:rotate(yRotation)
self.x, self.z =
self.x * math.cos(yRotation) + self.z * math.sin(yRotation),
- self.x * math.sin(yRotation) + self.z * math.cos(yRotation)
self.yRotation = yRotation
end
--- Get the local coordinates of a world position
---@param x number
---@param z number
---@return number, number x and z local coordinates
function Point:worldToLocal(x, z)
local lp = Point(x, z, 0)
lp:translate(-self.x, -self.z)
lp:rotate(-self.yRotation)
return lp.x, lp.z
end
--- Convert the local x z coordinates to world coordinates
---@param x number
---@param z number
---@return number, number x and z world coordinates
function Point:localToWorld(x, z)
local lp = Point(x, z, 0)
lp:rotate(self.yRotation)
lp:translate(self.x, self.z)
return lp.x, lp.z
end
---@class Waypoint : Point
Waypoint = CpObject(Point)
-- constructor from the legacy Courseplay waypoint
function Waypoint:init(cpWp, cpIndex)
self:set(cpWp, cpIndex)
end
function Waypoint:set(cpWp, cpIndex)
-- we initialize explicitly, no table copy as we want to have
-- full control over what is used in this object
-- can use course waypoints with cx/cz or turn waypoints with posX/posZ (but if revPos exists, that takes precedence
-- just like in the original turn code, don't ask me why there are two different values if we only use one...)
self.x = cpWp.x or cpWp.cx or cpWp.revPosX or cpWp.posX or 0
self.z = cpWp.z or cpWp.cz or cpWp.revPosZ or cpWp.posZ or 0
self.y = getTerrainHeightAtWorldPos(g_currentMission.terrainRootNode, self.x, 0, self.z)
self.angle = cpWp.angle or nil
self.radius = cpWp.radius or nil
self.rev = cpWp.rev or cpWp.turnReverse or cpWp.reverse or false
self.rev = self.rev or cpWp.gear and cpWp.gear == HybridAStar.Gear.Backward
self.speed = cpWp.speed
self.cpIndex = cpIndex or 0
self.turnStart = cpWp.turnStart
self.turnEnd = cpWp.turnEnd
self.interact = cpWp.wait or false
self.isConnectingTrack = cpWp.isConnectingTrack or nil
self.lane = cpWp.lane
self.ridgeMarker = cpWp.ridgeMarker
self.unload = cpWp.unload
self.mustReach = cpWp.mustReach
self.align = cpWp.align
self.headlandHeightForTurn = cpWp.headlandHeightForTurn
self.changeDirectionWhenAligned = cpWp.changeDirectionWhenAligned
end
--- Set from a generated waypoint (output of the course generator)
function Waypoint.initFromGeneratedWp(wp, ix)
local waypoint = Waypoint({})
waypoint.x = wp.x
waypoint.z = -wp.y
waypoint.y = getTerrainHeightAtWorldPos(g_currentMission.terrainRootNode, waypoint.x, 0, waypoint.z)
waypoint.cpIndex = ix or 0
waypoint.turnStart = wp.turnStart
waypoint.turnEnd = wp.turnEnd
waypoint.isConnectingTrack = wp.isConnectingTrack or nil
waypoint.lane = wp.passNumber and -wp.passNumber
waypoint.ridgeMarker = wp.ridgeMarker
return waypoint
end
--- Get the (original, non-offset) position of a waypoint
---@return number, number, number x, y, z
function Waypoint:getPosition()
return self.x, self.y, self.z
end
--- Get the offset position of a waypoint
---@param offsetX number left/right offset (right +, left -)
---@param offsetZ number forward/backward offset (forward +)
---@param dx number delta x to use (dx to the next waypoint by default)
---@param dz number delta z to use (dz to the next waypoint by default)
---@return number, number, number x, y, z
function Waypoint:getOffsetPosition(offsetX, offsetZ, dx, dz)
local x, y, z = self:getPosition()
local deltaX = dx or self.dx
local deltaZ = dz or self.dz
-- X offset should be inverted if we drive reverse here (left is always left regardless of the driving direction)
local reverse = self.reverseOffset and -1 or 1
if deltaX and deltaZ then
x = x - deltaZ * reverse * offsetX + deltaX * offsetZ
z = z + deltaX * reverse * offsetX + deltaZ * offsetZ
end
return x, y, z
end
function Waypoint:setOffsetPosition(offsetX, offsetZ, dx, dz)
self.x, self.y, self.z = self:getOffsetPosition(offsetX, offsetZ, dx, dz)
end
function Waypoint:getDistanceFromPoint(x, z)
return courseplay:distance(x, z, self.x, self.z)
end
function Waypoint:getDistanceFromVehicle(vehicle)
local vx, _, vz = getWorldTranslation(vehicle.cp.directionNode or vehicle.rootNode)
return self:getDistanceFromPoint(vx, vz)
end
-- a node related to a waypoint
---@class WaypointNode
WaypointNode = CpObject()
WaypointNode.MODE_NORMAL = 1
WaypointNode.MODE_LAST_WP = 2
WaypointNode.MODE_SWITCH_DIRECTION = 3
WaypointNode.MODE_SWITCH_TO_FORWARD = 4
WaypointNode.MODE_MUST_REACH = 5
function WaypointNode:init(name, logChanges)
self.logChanges = logChanges
self.node = courseplay.createNode(name, 0, 0, 0)
end
function WaypointNode:destroy()
courseplay.destroyNode(self.node)
end
---@param course Course
function WaypointNode:setToWaypoint(course, ix, suppressLog)
local newIx = math.min(ix, course:getNumberOfWaypoints())
if newIx ~= self.ix and self.logChanges and not suppressLog then
courseplay.debugVehicle(courseplay.DBG_PPC, course.vehicle, 'PPC: %s waypoint index %d', getName(self.node), ix)
end
self.ix = newIx
local x, y, z = course:getWaypointPosition(self.ix)
setTranslation(self.node, x, y, z)
setRotation(self.node, 0, course:getWaypointYRotation(self.ix), 0)
end
-- Allow ix > #Waypoints, in that case move the node lookAheadDistance beyond the last WP
function WaypointNode:setToWaypointOrBeyond(course, ix, distance)
--if self.ix and self.ix > ix then return end
if ix > course:getNumberOfWaypoints() then
-- beyond the last, so put it on the last for now
-- but use the direction of the one before the last as the last one's is bogus
self:setToWaypoint(course, course:getNumberOfWaypoints())
setRotation(self.node, 0, course:getWaypointYRotation(course:getNumberOfWaypoints() - 1), 0)
-- And now, move ahead a bit.
local nx, ny, nz = localToWorld(self.node, 0, 0, distance)
setTranslation(self.node, nx, ny, nz)
if self.logChanges and self.mode and self.mode ~= WaypointNode.MODE_LAST_WP then
courseplay.debugVehicle(courseplay.DBG_PPC, course.vehicle, 'PPC: last waypoint reached, moving node beyond last: %s', getName(self.node))
end
self.mode = WaypointNode.MODE_LAST_WP
elseif course:switchingToReverseAt(ix) or course:switchingToForwardAt(ix) then
-- just like at the last waypoint, if there's a direction switch, we want to drive up
-- to the waypoint so we move the goal point beyond it
-- the angle of ix is already pointing to reverse here
self:setToWaypoint(course, ix)
-- turn node back as this is the one before the first reverse, already pointing to the reverse direction.
local _, yRot, _ = getRotation(self.node)
setRotation(self.node, 0, yRot + math.pi, 0)
-- And now, move ahead a bit.
local nx, ny, nz = localToWorld(self.node, 0, 0, distance)
setTranslation(self.node, nx, ny, nz)
if self.logChanges and self.mode and self.mode ~= WaypointNode.MODE_SWITCH_DIRECTION then
courseplay.debugVehicle(courseplay.DBG_PPC, course.vehicle, 'PPC: switching direction at %d, moving node beyond it: %s', ix, getName(self.node))
end
self.mode = WaypointNode.MODE_SWITCH_DIRECTION
elseif course:mustReach(ix) then
-- TODO: this is actually the same as the last WP, should it be in the same elsif?
self:setToWaypoint(course, ix)
-- turn node to the incoming direction as we want to continue in the same direction until we reach it
setRotation(self.node, 0, course:getWaypointYRotation(ix - 1), 0)
-- And now, move ahead a bit.
local nx, ny, nz = localToWorld(self.node, 0, 0, distance)
setTranslation(self.node, nx, ny, nz)
if self.logChanges and self.mode and self.mode ~= WaypointNode.MODE_MUST_REACH then
courseplay.debugVehicle(courseplay.DBG_PPC, course.vehicle, 'PPC: must reach next waypoint, moving node beyond it: %s', getName(self.node))
end
self.mode = WaypointNode.MODE_MUST_REACH
else
if self.logChanges and self.mode and self.mode ~= WaypointNode.MODE_NORMAL then
courseplay.debugVehicle(courseplay.DBG_PPC, course.vehicle, 'PPC: normal waypoint (not last, no direction change: %s', getName(self.node))
end
self.mode = WaypointNode.MODE_NORMAL
self:setToWaypoint(course, ix)
end
end
---@class Course
Course = CpObject()
--- Course constructor
---@param waypoints Waypoint[] table of waypoints of the course
---@param temporary boolean optional, default false is this a temporary course?
-- @param first number optional, index of first waypoint to use
-- @param last number optional, index of last waypoint to use to construct of the course
function Course:init(vehicle, waypoints, temporary, first, last)
-- add waypoints from current vehicle course
---@type Waypoint[]
self.waypoints = self:initWaypoints()
local n = 0
for i = first or 1, last or #waypoints do
-- make sure we pass in the original vehicle.Waypoints index with n+first
table.insert(self.waypoints, Waypoint(waypoints[i], n + (first or 1)))
n = n + 1
end
-- offset to apply to every position
self.offsetX, self.offsetZ = 0, 0
self.temporaryOffsetX, self.temporaryOffsetZ = CpSlowChangingObject(0, 0), CpSlowChangingObject(0, 0)
self.numberOfHeadlands = 0
self.workWidth = 0
-- only for logging purposes
self.vehicle = vehicle
self.temporary = temporary or false
self.currentWaypoint = 1
self.length = 0
self.headlandLength = 0
self.totalTurns = 0
self:enrichWaypointData()
end
function Course.createFromGeneratedCourse(vehicle, waypoints, temporary, first, last)
local course = Course(vehicle, {}, temporary)
for i = first or 1, last or #waypoints do
table.insert(course.waypoints, Waypoint.initFromGeneratedWp(waypoints[i], i))
end
course:enrichWaypointData()
return course
end
function Course:initWaypoints()
return setmetatable({}, {
-- add a function to clamp the index between 1 and #self.waypoints
__index = function(tbl, key)
local result = rawget(tbl, key)
if not result and type(key) == "number" then
result = rawget(tbl, math.min(math.max(1, key), #tbl))
end
return result
end
})
end
--- Current offset to apply. getWaypointPosition() will always return the position adjusted by the
-- offset. The x and z offset are in the waypoint's coordinate system, waypoints are directed towards
-- the next waypoint, so a z = 1 offset will move the waypoint 1m forward, x = 1 1 m to the right (when
-- looking in the drive direction)
--- IMPORTANT: the offset for multitool (laneOffset) must not be part of this as it is already part of the
--- course,
--- @see Course#calculateOffsetCourse
function Course:setOffset(x, z)
self.offsetX, self.offsetZ = x, z
end
function Course:getOffset()
return self.offsetX, self.offsetZ
end
--- Temporary offset to apply. This is to use an offset temporarily without overwriting the normal offset of the course
function Course:setTemporaryOffset(x, z, t)
self.temporaryOffsetX:set(x, t)
self.temporaryOffsetZ:set(z, t)
end
function Course:changeTemporaryOffsetX(dx, t)
self.temporaryOffsetX:set(self.temporaryOffsetX:get() + dx, t)
end
function Course:setWorkWidth(w)
self.workWidth = w
end
function Course:getWorkWidth()
return self.workWidth
end
function Course:getNumberOfHeadlands()
return self.numberOfHeadlands
end
--- get number of waypoints in course
function Course:getNumberOfWaypoints()
return #self.waypoints
end
function Course:getWaypoint(ix)
return self.waypoints[ix]
end
--- Is this a temporary course? Can be used to differentiate between recorded and dynamically generated courses
-- The Course() object does not use this attribute for anything
function Course:isTemporary()
return self.temporary
end
-- add missing angles and world directions from one waypoint to the other
-- PPC relies on waypoint angles, the world direction is needed to calculate offsets
function Course:enrichWaypointData()
if #self.waypoints < 2 then return end
self.length = 0
self.headlandLength = 0
self.firstHeadlandWpIx = nil
self.firstCenterWpIx = nil
for i = 1, #self.waypoints - 1 do
self.waypoints[i].dToHere = self.length
self.waypoints[i].dToHereOnHeadland = self.headlandLength
local cx, _, cz = self:getWaypointPosition(i)
local nx, _, nz = self:getWaypointPosition(i + 1)
local dToNext = courseplay:distance(cx, cz, nx, nz)
self.waypoints[i].dToNext = dToNext
self.length = self.length + dToNext
if self:isOnHeadland(i) then
self.headlandLength = self.headlandLength + dToNext
self.firstHeadlandWpIx = self.firstHeadlandWpIx or i
else
-- TODO: this and firstHeadlandWpIx works only if there is one block on the field and
-- no islands, as then we have more than one group of headlands. But these are only
-- for the convoy mode anyway so it is ok if it does not work in all possible situations
self.firstCenterWpIx = self.firstCenterWpIx or i
end
if self:isTurnStartAtIx(i) then self.totalTurns = self.totalTurns + 1 end
if self:isTurnEndAtIx(i) then
self.dFromLastTurn = 0
elseif self.dFromLastTurn then
self.dFromLastTurn = self.dFromLastTurn + dToNext
end
self.waypoints[i].turnsToHere = self.totalTurns
self.waypoints[i].dx, _, self.waypoints[i].dz, _ = courseplay:getWorldDirection(cx, 0, cz, nx, 0, nz)
local dx, dz = MathUtil.vector2Normalize(nx - cx, nz - cz)
-- check for NaN
if dx == dx or dz == dz then
self.waypoints[i].yRot = MathUtil.getYRotationFromDirection(dx, dz)
else
self.waypoints[i].yRot = 0
end
self.waypoints[i].angle = math.deg(self.waypoints[i].yRot)
self.waypoints[i].calculatedRadius = self:calculateRadius(i)
if (self:isReverseAt(i) and not self:switchingToForwardAt(i)) or self:switchingToReverseAt(i) then
-- X offset must be reversed at waypoints where we are driving in reverse
self.waypoints[i].reverseOffset = true
end
if self.waypoints[i].lane and self.waypoints[i].lane < 0 then
self.numberOfHeadlands = math.max(self.numberOfHeadlands, -self.waypoints[i].lane)
end
end
-- make the last waypoint point to the same direction as the previous so we don't
-- turn towards the first when ending the course. (the course generator points the last
-- one to the first, should probably be changed there)
self.waypoints[#self.waypoints].angle = self.waypoints[#self.waypoints - 1].angle
self.waypoints[#self.waypoints].yRot = self.waypoints[#self.waypoints - 1].yRot
self.waypoints[#self.waypoints].dx = self.waypoints[#self.waypoints - 1].dx
self.waypoints[#self.waypoints].dz = self.waypoints[#self.waypoints - 1].dz
self.waypoints[#self.waypoints].dToNext = 0
self.waypoints[#self.waypoints].dToHere = self.length
self.waypoints[#self.waypoints].dToHereOnHeadland = self:isOnHeadland(#self.waypoints - 1) and
self.waypoints[#self.waypoints - 1].dToHereOnHeadland + self.waypoints[#self.waypoints - 1].dToNext or
self.waypoints[#self.waypoints - 1].dToHereOnHeadland
self.waypoints[#self.waypoints].turnsToHere = self.totalTurns
self.waypoints[#self.waypoints].calculatedRadius = self:calculateRadius(#self.waypoints)
self.waypoints[#self.waypoints].reverseOffset = self:isReverseAt(#self.waypoints)
-- now add some metadata for the combines
local dToNextTurn, lNextRow, nextRowStartIx = 0, 0, 0
local turnFound = false
for i = #self.waypoints - 1, 1, -1 do
if turnFound then
dToNextTurn = dToNextTurn + self.waypoints[i].dToNext
self.waypoints[i].dToNextTurn = dToNextTurn
self.waypoints[i].lNextRow = lNextRow
self.waypoints[i].nextRowStartIx = nextRowStartIx
end
if self:isTurnStartAtIx(i) then
lNextRow = dToNextTurn
nextRowStartIx = i + 1
dToNextTurn = 0
turnFound = true
end
end
courseplay.debugFormat(courseplay.DBG_COURSES, 'Course with %d waypoints created/updated, %.1f meters, %d turns', #self.waypoints, self.length, self.totalTurns)
end
function Course:calculateRadius(ix)
local deltaAngleDeg = math.deg(getDeltaAngle(self.waypoints[ix].yRot, self.waypoints[ix - 1].yRot))
return math.abs( self:getDistanceToNextWaypoint(ix) / ( 2 * math.asin( math.rad(deltaAngleDeg) / 2 )))
end
--- Is this the same course as otherCourse?
-- TODO: is there a hash we could use instead?
function Course:equals(other)
if #self.waypoints ~= #other.waypoints then return false end
-- for now just check the coordinates of the first waypoint
if self.waypoints[1].x - other.waypoints[1].x > 0.01 then return false end
if self.waypoints[1].z - other.waypoints[1].z > 0.01 then return false end
-- same number of waypoints, first waypoint same coordinates, equals!
return true
end
--- A super simple hash to identify and compare courses (see convoy)
function Course:getHash()
local hash = ''
for i = 1, math.min(20, #self.waypoints) do
hash = hash .. string.format('%d%d', self.waypoints[i].x, self.waypoints[i].z)
end
return hash
end
function Course:setCurrentWaypointIx(ix)
self.currentWaypoint = ix
end
function Course:getCurrentWaypointIx()
return self.currentWaypoint
end
function Course:setLastPassedWaypointIx(ix)
self.lastPassedWaypoint = ix
end
function Course:getLastPassedWaypointIx()
return self.lastPassedWaypoint
end
function Course:isReverseAt(ix)
return self.waypoints[math.min(math.max(1, ix), #self.waypoints)].rev
end
function Course:getLastReverseAt(ix)
for i=ix,#self.waypoints do
if not self.waypoints[i].rev then
return i-1
end
end
end
function Course:isForwardOnly()
for _, wp in ipairs(self.waypoints) do
if wp.rev then
return false
end
end
return true
end
function Course:isTurnStartAtIx(ix)
return self.waypoints[ix].turnStart
end
function Course:isTurnEndAtIx(ix)
return self.waypoints[ix].turnEnd
end
function Course:skipOverTurnStart(ix)
if self:isTurnStartAtIx(ix) then
return ix + 1
else
return ix
end
end
--- Is this waypoint on a connecting track, that is, a transfer path between
-- a headland and the up/down rows where there's no fieldwork to do.
function Course:isOnConnectingTrack(ix)
return self.waypoints[ix].isConnectingTrack
end
--- Is this a waypoint we must reach (keep driving towards it until we reach it, no cutting corners,
-- for example the end of a worked row to not miss anything)
function Course:mustReach(ix)
return self.waypoints[math.min(math.max(1, ix), #self.waypoints)].mustReach
end
function Course:switchingDirectionAt(ix)
return self:switchingToForwardAt(ix) or self:switchingToReverseAt(ix)
end
function Course:getNextDirectionChangeFromIx(ix)
for i = ix, #self.waypoints do
if self:switchingDirectionAt(i) then
return i
end
end
end
function Course:getNextWaitPointFromIx(ix)
for i = ix, #self.waypoints do
if self:isWaitAt(i) then
return i
end
end
end
function Course:switchingToReverseAt(ix)
return not self:isReverseAt(ix) and self:isReverseAt(ix + 1)
end
function Course:switchingToForwardAt(ix)
return self:isReverseAt(ix) and not self:isReverseAt(ix + 1)
end
function Course:isUnloadAt(ix)
return self.waypoints[ix].unload
end
function Course:isWaitAt(ix)
return self.waypoints[ix].interact
end
function Course:getHeadlandNumber(ix)
return self.waypoints[ix].lane
end
function Course:isOnHeadland(ix, n)
ix = ix or self.currentWaypoint
if n then
return self.waypoints[ix].lane and self.waypoints[ix].lane == -n
else
return self.waypoints[ix].lane and self.waypoints[ix].lane < 0
end
end
function Course:isOnOutermostHeadland(ix)
return self.waypoints[ix].lane and self.waypoints[ix].lane == -1
end
function Course:isChangeDirectionWhenAligned(ix)
return self.waypoints[ix].changeDirectionWhenAligned
end
function Course:useTightTurnOffset(ix)
return self.waypoints[ix].useTightTurnOffset
end
--- Returns the position of the waypoint at ix with the current offset applied.
---@return number, number, number x, y, z
function Course:getWaypointPosition(ix)
if self:isTurnStartAtIx(ix) then
-- turn start waypoints point to the turn end wp, for example at the row end they point 90 degrees to the side
-- from the row direction. This is a problem when there's an offset so use the direction of the previous wp
-- when calculating the offset for a turn start wp.
return self:getOffsetPositionWithOtherWaypointDirection(ix, ix - 1)
else
return self.waypoints[ix]:getOffsetPosition(self.offsetX + self.temporaryOffsetX:get(), self.offsetZ + self.temporaryOffsetZ:get())
end
end
---Return the offset coordinates of waypoint ix as if it was pointing to the same direction as waypoint ixDir
function Course:getOffsetPositionWithOtherWaypointDirection(ix, ixDir)
return self.waypoints[ix]:getOffsetPosition(self.offsetX + self.temporaryOffsetX:get(), self.offsetZ + self.temporaryOffsetZ:get(),
self.waypoints[ixDir].dx, self.waypoints[ixDir].dz)
end
-- distance between (px,pz) and the ix waypoint
function Course:getDistanceBetweenPointAndWaypoint(px, pz, ix)
return self.waypoints[ix]:getDistanceFromPoint(px, pz)
end
function Course:getDistanceBetweenVehicleAndWaypoint(vehicle, ix)
return self.waypoints[ix]:getDistanceFromVehicle(vehicle)
end
--- get waypoint position in the node's local coordinates
function Course:getWaypointLocalPosition(node, ix)
local x, y, z = self:getWaypointPosition(ix)
local dx, dy, dz = worldToLocal(node, x, y, z)
return dx, dy, dz
end
function Course:havePhysicallyPassedWaypoint(node, ix)
local _, _, dz = self:getWaypointLocalPosition(node, ix)
return dz < 0;
end
function Course:getWaypointAngleDeg(ix)
return self.waypoints[math.min(#self.waypoints, ix)].angle
end
--- Gets the world directions of the waypoint.
---@param ix number
---@return dx x world direction
---@return dz z world direction
function Course:getWaypointWorldDirections(ix)
local wp = self.waypoints[math.min(#self.waypoints, ix)]
return wp.dx,wp.dz
end
-- This is the radius from the course generator. For now ony island bypass waypoints nodes have a
-- radius.
function Course:getRadiusAtIx(ix)
local r = self.waypoints[ix].radius
if r ~= r then
-- radius can be nan
return nil
else
return r
end
end
-- This is the radius calculated when the course is created.
function Course:getCalculatedRadiusAtIx(ix)
local r = self.waypoints[ix].calculatedRadius
if r ~= r then
-- radius can be nan
return nil
else
return r
end
end
--- Get the minimum radius within d distance from waypoint ix
---@param ix number waypoint index to start
---@param d number distance in meters to look forward
---@return number the minimum radius within d distance from waypoint ix
function Course:getMinRadiusWithinDistance(ix, d)
local ixAtD = self:getNextWaypointIxWithinDistance(ix, d) or ix
local minR, count = math.huge, 0
for i = ix, ixAtD do
if self:isTurnStartAtIx(i) or self:isTurnEndAtIx(i) then
-- the turn maneuver code will take care of speed
return nil
end
local r = self:getCalculatedRadiusAtIx(i)
if r and r < minR then
count = count + 1
minR = r
end
end
return count > 0 and minR or nil
end
--- Get the Y rotation of a waypoint (pointing into the direction of the next)
function Course:getWaypointYRotation(ix)
local i = ix
-- at the last waypoint use the incoming direction
if ix >= #self.waypoints then
i = #self.waypoints - 1
elseif ix < 1 then
i = 1
end
local cx, _, cz = self:getWaypointPosition(i)
local nx, _, nz = self:getWaypointPosition(i + 1)
local dx, dz = MathUtil.vector2Normalize(nx - cx, nz - cz)
-- check for NaN
if dx ~= dx or dz ~= dz then return 0 end
return MathUtil.getYRotationFromDirection(dx, dz)
end
function Course:getRidgeMarkerState(ix)
return self.waypoints[ix].ridgeMarker or 0
end
--- Get the average speed setting across n waypoints starting at ix
function Course:getAverageSpeed(ix, n)
local total, count = 0, 0
for i = ix, ix + n - 1 do
local index = self:getIxRollover(i)
if self.waypoints[index].speed ~= nil and self.waypoints[index].speed ~= 0 then
total = total + self.waypoints[index].speed
count = count + 1
end
end
return (total > 0 and count > 0) and (total / count) or nil
end
function Course:getIxRollover(ix)
if ix > #self.waypoints then
return ix - #self.waypoints
elseif ix < 1 then
return #self.waypoints - ix
end
return ix
end
function Course:isLastWaypointIx(ix)
return #self.waypoints == ix
end
function Course:print()
for i = 1, #self.waypoints do
local p = self.waypoints[i]
print(string.format('%d: x=%.1f z=%.1f a=%.1f yRot=%.1f ts=%s te=%s r=%s i=%s d=%.1f t=%d l=%s p=%s',
i, p.x, p.z, p.angle or -1, math.deg(p.yRot or 0),
tostring(p.turnStart), tostring(p.turnEnd), tostring(p.rev), tostring(p.interact),
p.dToHere or -1, p.turnsToHere or -1, tostring(p.lane), tostring(p.pipeInFruit)))
end
end
function Course:getDistanceToNextWaypoint(ix)
return self.waypoints[math.min(#self.waypoints, ix)].dToNext
end
function Course:getDistanceBetweenWaypoints(a, b)
return math.abs(self.waypoints[a].dToHere - self.waypoints[b].dToHere)
end
function Course:getDistanceFromFirstWaypoint(ix)
return self.waypoints[ix].dToHere
end
function Course:getDistanceToLastWaypoint(ix)
return self.length - self.waypoints[ix].dToHere
end
function Course:getWaypointsWithinDrivingTime(startIx, fwd, seconds, speed)
local waypoints = {}
local travelTimeSeconds = 0
local first, last, step = startIx, #self.waypoints - 1, 1
if not fwd then
first, last, step = startIx - 1, 1, -1
end
for i = startIx, #self.waypoints - 1 do
table.insert(waypoints, self.waypoints[i])
local v = speed or self.waypoints[i].speed or 10
local s = self:getDistanceToNextWaypoint(i)
travelTimeSeconds = travelTimeSeconds + s / (v / 3.6)
if travelTimeSeconds > seconds then
break
end
end
return waypoints
end
--- How far are we from the waypoint marked as the beginning of the up/down rows?
---@param ix number start searching from this index. Will stop searching after 100 m
---@return number of meters or math.huge if no start up/down row waypoint found within 100 meters and the index of the first up/down waypoint
function Course:getDistanceToFirstUpDownRowWaypoint(ix)
local d = 0
local isConnectingTrack = false
for i = ix, #self.waypoints - 1 do
isConnectingTrack = isConnectingTrack or self.waypoints[i].isConnectingTrack
d = d + self.waypoints[i].dToNext
if self.waypoints[i].lane and not self.waypoints[i + 1].lane and isConnectingTrack then
return d, i + 1
end
if d > 1000 then
return math.huge, nil
end
end
return math.huge, nil
end
--- Find the waypoint with the original index cpIx in vehicle.Waypoints
-- This is needed when legacy code like turn or reverse finishes and continues the
-- course at at given waypoint. The index of that waypoint may be different when
-- we have combined courses, so here find the correct one.
function Course:findOriginalIx(cpIx)
for i = 1, #self.waypoints do
if self.waypoints[i].cpIndex == cpIx then
return i
end
end
return 1
end
--- Is any of the waypoints around ix an unload point?
---@param ix number waypoint index to look around
---@param forward number look forward this number of waypoints when searching
---@param backward number look back this number of waypoints when searching
---@return boolean true if any of the waypoints are unload points and the index of the next unload point
function Course:hasUnloadPointAround(ix, forward, backward)
return self:hasWaypointWithPropertyAround(ix, forward, backward, function(p) return p.unload end)
end
--- Is any of the waypoints around ix a wait point?
---@param ix number waypoint index to look around
---@param forward number look forward this number of waypoints when searching
---@param backward number look back this number of waypoints when searching
---@return boolean true if any of the waypoints are wait points and the index of the next wait point
function Course:hasWaitPointAround(ix, forward, backward)
-- TODO: clarify if we use interact or wait or both?
return self:hasWaypointWithPropertyAround(ix, forward, backward, function(p) return p.wait or p.interact end)
end
function Course:hasWaypointWithPropertyAround(ix, forward, backward, hasProperty)
for i = math.max(ix - backward + 1, 1), math.min(ix + forward - 1, #self.waypoints) do
if hasProperty(self.waypoints[i]) then
-- one of the waypoints around ix has this property
return true, i
end
end
return false
end
--- Is there an unload waypoint within distance around ix?
---@param ix number waypoint index to look around
---@param distance number distance in meters to look around the waypoint
---@return boolean true if any of the waypoints are unload points and the index of the next unload point
function Course:hasUnloadPointWithinDistance(ix, distance)
return self:hasWaypointWithPropertyWithinDistance(ix, distance, function(p) return p.unload end)
end
--- Is there a wait waypoint within distance around ix?
---@param ix number waypoint index to look around
---@param distance number distance in meters to look around the waypoint
---@return boolean true if any of the waypoints are wait points and the index of that wait point
function Course:hasWaitPointWithinDistance(ix, distance)
return self:hasWaypointWithPropertyWithinDistance(ix, distance, function(p) return p.wait or p.interact end)
end
--- Is there an turn (start or end) around ix?
---@param ix number waypoint index to look around
---@param distance number distance in meters to look around the waypoint
---@return boolean true if any of the waypoints are turn start/end point
function Course:hasTurnWithinDistance(ix, distance)
return self:hasWaypointWithPropertyWithinDistance(ix, distance, function(p) return p.turnStart or p.turnEnd end)
end
function Course:hasWaypointWithPropertyWithinDistance(ix, distance, hasProperty)
-- search backwards first
local d = 0
for i = math.max(1, ix - 1), 1, -1 do
if hasProperty(self.waypoints[i]) then
return true, i
end
d = d + self.waypoints[i].dToNext
if d > distance then break end
end
-- search forward
d = 0
for i = ix, #self.waypoints - 1 do
if hasProperty(self.waypoints[i]) then
return true, i
end
d = d + self.waypoints[i].dToNext
if d > distance then break end
end
return false
end
--- Get the index of the first waypoint from ix which is at least distance meters away
---@param backward boolean search backward if true
---@return number, number index and exact distance
function Course:getNextWaypointIxWithinDistance(ix, distance, backward)
local d = 0
local from, to, step = ix, #self.waypoints - 1, 1
if backward then
from, to, step = ix - 1, 1, -1
end
for i = from, to, step do
d = d + self.waypoints[i].dToNext
if d > distance then return i + 1, d end
end
-- at the end/start of course return last/first wp
return to + 1, d
end
--- Get the index of the first waypoint from ix which is at least distance meters away (search backwards)
function Course:getPreviousWaypointIxWithinDistance(ix, distance)
local d = 0
for i = math.max(1, ix - 1), 1, -1 do
d = d + self.waypoints[i].dToNext
if d > distance then return i end
end
return nil
end
--- Collect a nSteps number of positions on the course, starting at startIx, one position for every second,
--- or every dStep meters, whichever is less
---@param startIx number start at this waypoint
---@param dStep number step in meters
---@param nSteps number number of positions to collect
function Course:getPositionsOnCourse(nominalSpeed, startIx, dStep, nSteps)
local function addPosition(positions, ix, x, y, z, dFromLastWp, speed)
table.insert(positions, {x = x + dFromLastWp * self.waypoints[ix].dx,
y = y,
z = z + dFromLastWp * self.waypoints[ix].dz,
yRot = self.waypoints[ix].yRot,
speed = speed,
-- for debugging only
dToNext = self.waypoints[ix].dToNext,
dFromLastWp = dFromLastWp,
ix = ix})
end
local positions = {}
local d = 0 -- distance from the last step
local dFromLastWp = 0
local ix = startIx
while #positions < nSteps and ix < #self.waypoints do
local speed = nominalSpeed
if self.waypoints[ix].speed then
speed = (self.waypoints[ix].speed > 0) and self.waypoints[ix].speed or nominalSpeed
end
-- speed / 3.6 is the speed in meter/sec, that's how many meters we travel in one sec
-- don't step more than 4 m as that would move the boxes too far away from each other creating a gap between them
-- so if we drive fast, our event horizon shrinks, which is probably not a good thing
local currentStep = math.min(speed / 3.6, dStep)
local x, y, z = self:getWaypointPosition(ix)
if dFromLastWp + currentStep < self.waypoints[ix].dToNext then
while dFromLastWp + currentStep < self.waypoints[ix].dToNext and #positions < nSteps and ix < #self.waypoints do
d = d + currentStep
dFromLastWp = dFromLastWp + currentStep
addPosition(positions, ix, x, y, z, dFromLastWp, speed)
end
-- this is before wp ix, so negative
dFromLastWp = - (self.waypoints[ix].dToNext - dFromLastWp)
d = 0
ix = ix + 1
else
d = - dFromLastWp
-- would step over the waypoint
while d < currentStep and ix < #self.waypoints do
d = d + self.waypoints[ix].dToNext
ix = ix + 1
end
-- this is before wp ix, so negative
dFromLastWp = - (d - currentStep)
d = 0
x, y, z = self:getWaypointPosition(ix)
addPosition(positions, ix, x, y, z, dFromLastWp, speed)
end
end
return positions
end
function Course:getLength()
return self.length
end
--- Is there a turn between the two waypoints?
function Course:isTurnBetween(ix1, ix2)
return self.waypoints[ix1].turnsToHere ~= self.waypoints[ix2].turnsToHere
end
function Course:getRemainingDistanceAndTurnsFrom(ix)
local distance = self.length - self.waypoints[ix].dToHere
local numTurns = self.totalTurns - self.waypoints[ix].turnsToHere
return distance, numTurns
end
function Course:getNextFwdWaypointIx(ix)
for i = ix, #self.waypoints do
if not self:isReverseAt(i) then
return i
end
end
courseplay.debugFormat(courseplay.DBG_COURSES, 'Course: could not find next forward waypoint after %d', ix)
return ix
end
function Course:getNextFwdWaypointIxFromVehiclePosition(ix, vehicleNode, lookAheadDistance)
for i = ix, #self.waypoints do
if not self:isReverseAt(i) then
local uX, uY, uZ = self:getWaypointPosition(i)
local _, _, z = worldToLocal(vehicleNode, uX, uY, uZ);
if z > lookAheadDistance then
return i
end