Skip to content

Commit 83f20e8

Browse files
antler22claude
andcommitted
Refactor: extract isManualCombine() helper and checkCombineRelocatedAndRepath()
Per pvaiko review: - Add isManualCombine() to AIDriveStrategyUnloadCombine — single place to check whether the target is a CpManualCombineProxy; replaces five inconsistent isManualProxy field-access patterns across the file - Extract the driveToCombine re-path block into checkCombineRelocatedAndRepath() so driveToCombine() stays clean and concise - All callers updated to use self:isManualCombine() Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
1 parent 16694e3 commit 83f20e8

1 file changed

Lines changed: 50 additions & 51 deletions

File tree

scripts/ai/strategies/AIDriveStrategyUnloadCombine.lua

Lines changed: 50 additions & 51 deletions
Original file line numberDiff line numberDiff line change
@@ -336,6 +336,14 @@ function AIDriveStrategyUnloadCombine:getCombineStrategy()
336336
return nil
337337
end
338338

339+
--- Returns true when the assigned combine is a manually-driven combine (CpManualCombineProxy),
340+
--- false for CP-driven combines or when no combine is assigned.
341+
---@return boolean
342+
function AIDriveStrategyUnloadCombine:isManualCombine()
343+
local strategy = self:getCombineStrategy()
344+
return strategy ~= nil and strategy.isManualProxy ~= nil
345+
end
346+
339347
--- Checks if the assigned combine is active (either CP-driven or manually calling a grain cart).
340348
---@return boolean
341349
function AIDriveStrategyUnloadCombine:isCombineActive()
@@ -386,8 +394,7 @@ function AIDriveStrategyUnloadCombine:getDriveData(dt, vX, vY, vZ)
386394
-- The placeholder follow course is static and the cart will drift from it as the combine moves,
387395
-- so the off-track check would otherwise stop the job. The timeout (5000 ms) is much larger
388396
-- than any realistic frame interval, so as long as this runs every frame the check stays off.
389-
local combineStrategyForOffTrack = self:getCombineStrategy()
390-
if combineStrategyForOffTrack and combineStrategyForOffTrack.isManualProxy then
397+
if self:isManualCombine() then
391398
self.ppc:disableStopWhenOffTrack(5000)
392399
end
393400

@@ -709,7 +716,7 @@ function AIDriveStrategyUnloadCombine:driveBesideCombine()
709716
-- the live pipe reference node and stays locked to the combine's current heading, including
710717
-- through curves. For CP-driven combines keep the original behaviour: only override the PPC
711718
-- course-based goal point when the cart is still far behind the pipe (dz > 5).
712-
local isManual = strategy.isManualProxy and strategy:isManualProxy()
719+
local isManual = self:isManualCombine()
713720
-- Calculate an artificial goal point relative to the harvester to align better when starting to unload
714721
if dz > 5 or isManual then
715722
_, _, dz = localToLocal(self.vehicle:getAIDirectionNode(), self:getPipeOffsetReferenceNode(), 0, 0, 0)
@@ -1467,7 +1474,7 @@ function AIDriveStrategyUnloadCombine:setupFollowCourse()
14671474
-- starting at the combine's current position and heading. The PPC needs a course to
14681475
-- initialise against, but driveBesideCombine() overrides all steering with a live goal
14691476
-- point derived from the pipe reference node, so this course is never actually followed.
1470-
if combineStrategy and combineStrategy:isManualProxy() then
1477+
if self:isManualCombine() then
14711478
local placeholder = Course.createStraightForwardCourse(self.combineToUnload, 100, 0,
14721479
self.combineToUnload:getAIDirectionNode())
14731480
if placeholder then
@@ -1961,6 +1968,43 @@ function AIDriveStrategyUnloadCombine:checkForCombineTurnArea()
19611968
end
19621969
end
19631970

1971+
--- For manually-driven combines: if the combine has moved significantly since the approach
1972+
--- course was generated, trigger a fast A* re-path to its new position.
1973+
--- Only fires for manual combines — CP combines use their own rendezvous/waypoint system.
1974+
--- Guards: checks every 5 s; skips when <20 m of course remains or within 25 m of combine;
1975+
--- only re-paths when combine has moved ≥ 30 m (genuine relocation, not minor drift).
1976+
--- Uses HybridAStar.defaultMaxIterations to keep the search sub-second on any field size.
1977+
---@return boolean true when a re-path was triggered (caller should return immediately)
1978+
function AIDriveStrategyUnloadCombine:checkCombineRelocatedAndRepath()
1979+
if not self:isManualCombine() then return false end
1980+
if g_time - (self.lastCombinePositionCheckTime or 0) <= 5000 then return false end
1981+
self.lastCombinePositionCheckTime = g_time
1982+
local remainingDist = self.course:getDistanceToLastWaypoint(self.course:getCurrentWaypointIx())
1983+
local distToCombine = self:getDistanceFromCombine()
1984+
if remainingDist <= 20 or distToCombine <= 25 then return false end
1985+
local cX, _, cZ = getWorldTranslation(self:getPipeOffsetReferenceNode())
1986+
local lastX = self.combinePositionAtApproachStart and self.combinePositionAtApproachStart.x or cX
1987+
local lastZ = self.combinePositionAtApproachStart and self.combinePositionAtApproachStart.z or cZ
1988+
if MathUtil.vector2Length(cX - lastX, cZ - lastZ) < 30 then return false end
1989+
local xOffset, zOffset = self:getPipeOffset(self.combineToUnload)
1990+
zOffset = -self:getCombinesMeasuredBackDistance() - 3
1991+
self:debug('combine moved, re-pathfinding to new position')
1992+
self.combinePositionAtApproachStart = { x = cX, z = cZ }
1993+
local context = PathfinderContext(self.vehicle)
1994+
context:maxFruitPercent(self:getMaxFruitPercent(self:getPipeOffsetReferenceNode(), xOffset, zOffset))
1995+
context:offFieldPenalty(self:getOffFieldPenalty(self.combineToUnload))
1996+
context:useFieldNum(CpFieldUtil.getFieldNumUnderVehicle(self.combineToUnload))
1997+
context:areaToAvoid(self:getCombineStrategy():getAreaToAvoid())
1998+
context:vehiclesToIgnore({ self.combineToUnload })
1999+
context:maxIterations(HybridAStar.defaultMaxIterations)
2000+
self.pathfinderController:registerListeners(self, self.onPathfindingDoneToWaitingCombine,
2001+
self.onPathfindingFailedToMovingTarget, self.onPathfindingObstacleAtStart)
2002+
self.pathfinderController:findPathToNode(context, self:getPipeOffsetReferenceNode(),
2003+
xOffset or 0, zOffset or 0, 3)
2004+
self:setNewState(self.states.WAITING_FOR_PATHFINDER)
2005+
return true
2006+
end
2007+
19642008
------------------------------------------------------------------------------------------------------------------------
19652009
-- Drive to stopped combine
19662010
------------------------------------------------------------------------------------------------------------------------
@@ -1972,52 +2016,7 @@ function AIDriveStrategyUnloadCombine:driveToCombine()
19722016

19732017
self:getCombineStrategy():reconfirmRendezvous()
19742018

1975-
-- For manually-driven combines only: if the combine has moved significantly since the
1976-
-- approach course was generated, re-pathfind to its new position so we don't drive to
1977-
-- an empty spot. CP combines use their own rendezvous/waypoint system and must not be
1978-
-- affected by this extra re-dispatch.
1979-
-- Guards keep this infrequent and fast:
1980-
-- • only check every 5 s (cheap distance math)
1981-
-- • skip if remaining course < 20 m (almost there — let proximity handling finish)
1982-
-- • skip if already within 25 m of the combine (driveBesideCombine takes over soon)
1983-
-- • only trigger when the combine has actually moved ≥ 30 m (genuine relocation)
1984-
-- Uses a capped iteration count (defaultMaxIterations) so the A* search completes in
1985-
-- well under a second on any field size, minimising the WAITING_FOR_PATHFINDER stop.
1986-
local combineStrategyForRepath = self:getCombineStrategy()
1987-
if combineStrategyForRepath and combineStrategyForRepath.isManualProxy and
1988-
g_time - (self.lastCombinePositionCheckTime or 0) > 5000 then
1989-
self.lastCombinePositionCheckTime = g_time
1990-
local remainingDist = self.course:getDistanceToLastWaypoint(self.course:getCurrentWaypointIx())
1991-
local distToCombine = self:getDistanceFromCombine()
1992-
if remainingDist > 20 and distToCombine > 25 then
1993-
local cX, _, cZ = getWorldTranslation(self:getPipeOffsetReferenceNode())
1994-
local lastX = self.combinePositionAtApproachStart and self.combinePositionAtApproachStart.x or cX
1995-
local lastZ = self.combinePositionAtApproachStart and self.combinePositionAtApproachStart.z or cZ
1996-
local moved = MathUtil.vector2Length(cX - lastX, cZ - lastZ)
1997-
if moved >= 30 then
1998-
local xOffset, zOffset = self:getPipeOffset(self.combineToUnload)
1999-
zOffset = -self:getCombinesMeasuredBackDistance() - 3
2000-
self:debug('driveToCombine: combine moved %.1f m, re-pathfinding to new position', moved)
2001-
self.combinePositionAtApproachStart = { x = cX, z = cZ }
2002-
-- Fast re-path: cap iterations at the default (avoids multi-second searches on
2003-
-- large fields) and ignore the combine as an obstacle so the path finds the gap
2004-
-- behind it rather than routing around the vehicle body.
2005-
local context = PathfinderContext(self.vehicle)
2006-
context:maxFruitPercent(self:getMaxFruitPercent(self:getPipeOffsetReferenceNode(), xOffset, zOffset))
2007-
context:offFieldPenalty(self:getOffFieldPenalty(self.combineToUnload))
2008-
context:useFieldNum(CpFieldUtil.getFieldNumUnderVehicle(self.combineToUnload))
2009-
context:areaToAvoid(self:getCombineStrategy():getAreaToAvoid())
2010-
context:vehiclesToIgnore({ self.combineToUnload })
2011-
context:maxIterations(HybridAStar.defaultMaxIterations)
2012-
self.pathfinderController:registerListeners(self, self.onPathfindingDoneToWaitingCombine,
2013-
self.onPathfindingFailedToMovingTarget, self.onPathfindingObstacleAtStart)
2014-
self.pathfinderController:findPathToNode(context, self:getPipeOffsetReferenceNode(),
2015-
xOffset or 0, zOffset or 0, 3)
2016-
self:setNewState(self.states.WAITING_FOR_PATHFINDER)
2017-
return
2018-
end
2019-
end
2020-
end
2019+
if self:checkCombineRelocatedAndRepath() then return end
20212020

20222021
-- towards the end of the course we start checking if we can already switch to unload
20232022
if self.course:getDistanceToLastWaypoint(self.course:getCurrentWaypointIx()) < 15 and
@@ -2151,7 +2150,7 @@ function AIDriveStrategyUnloadCombine:unloadMovingCombine()
21512150
-- The farmer is in full control: ignore fill level, alignment, turning state, etc.
21522151
-- Stay under the pipe until the proxy's isUnloadFinished() fires (pipe closed for 2s)
21532152
-- or the grain cart's own trailer fills up (handled by changeToUnloadWhenTrailerFull above).
2154-
if combineStrategy.isManualProxy then
2153+
if self:isManualCombine() then
21552154
self:debugSparse('unloadMovingCombine (manual): isDischarging=%s',
21562155
tostring(combineStrategy:isDischarging()))
21572156
return gx, gz

0 commit comments

Comments
 (0)