Merge pull request #1350 from FlightControl-Master/FF/Ops

OPS Update
This commit is contained in:
Frank 2020-09-20 00:26:10 +02:00 committed by GitHub
commit 6445cf01a2
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
21 changed files with 8680 additions and 2945 deletions

View File

@ -0,0 +1,898 @@
--- **Core** - A* Pathfinding.
--
-- **Main Features:**
--
-- * Find path from A to B.
-- * Pre-defined as well as custom valid neighbour functions.
-- * Pre-defined as well as custom cost functions.
-- * Easy rectangular grid setup.
--
-- ===
--
-- ### Author: **funkyfranky**
-- @module Core.Astar
-- @image CORE_Astar.png
--- ASTAR class.
-- @type ASTAR
-- @field #string ClassName Name of the class.
-- @field #boolean Debug Debug mode. Messages to all about status.
-- @field #string lid Class id string for output to DCS log file.
-- @field #table nodes Table of nodes.
-- @field #number counter Node counter.
-- @field #number Nnodes Number of nodes.
-- @field #number nvalid Number of nvalid calls.
-- @field #number nvalidcache Number of cached valid evals.
-- @field #number ncost Number of cost evaluations.
-- @field #number ncostcache Number of cached cost evals.
-- @field #ASTAR.Node startNode Start node.
-- @field #ASTAR.Node endNode End node.
-- @field Core.Point#COORDINATE startCoord Start coordinate.
-- @field Core.Point#COORDINATE endCoord End coordinate.
-- @field #function ValidNeighbourFunc Function to check if a node is valid.
-- @field #table ValidNeighbourArg Optional arguments passed to the valid neighbour function.
-- @field #function CostFunc Function to calculate the heuristic "cost" to go from one node to another.
-- @field #table CostArg Optional arguments passed to the cost function.
-- @extends Core.Base#BASE
--- **When nothing goes right... Go left!**
--
-- ===
--
-- ![Banner Image](..\Presentations\Astar\ASTAR_Main.jpg)
--
-- # The ASTAR Concept
--
-- Pathfinding algorithm.
--
--
-- # Start and Goal
--
-- The first thing we need to define is obviously the place where we want to start and where we want to go eventually.
--
-- ## Start
--
-- The start
--
-- ## Goal
--
--
-- # Nodes
--
-- ## Rectangular Grid
--
-- A rectangular grid can be created using the @{#ASTAR.CreateGrid}(*ValidSurfaceTypes, BoxHY, SpaceX, deltaX, deltaY, MarkGrid*), where
--
-- * *ValidSurfaceTypes* is a table of valid surface types. By default all surface types are valid.
-- * *BoxXY* is the width of the grid perpendicular the the line between start and end node. Default is 40,000 meters (40 km).
-- * *SpaceX* is the additional space behind the start and end nodes. Default is 20,000 meters (20 km).
-- * *deltaX* is the grid spacing between nodes in the direction of start and end node. Default is 2,000 meters (2 km).
-- * *deltaY* is the grid spacing perpendicular to the direction of start and end node. Default is the same as *deltaX*.
-- * *MarkGrid* If set to *true*, this places marker on the F10 map on each grid node. Note that this can stall DCS if too many nodes are created.
--
-- ## Valid Surfaces
--
-- Certain unit types can only travel on certain surfaces types, for example
--
-- * Naval units can only travel on water (that also excludes shallow water in DCS currently),
-- * Ground units can only traval on land.
--
-- By restricting the surface type in the grid construction, we also reduce the number of nodes, which makes the algorithm more efficient.
--
-- ## Box Width (BoxHY)
--
-- The box width needs to be large enough to capture all paths you want to consider.
--
-- ## Space in X
--
-- The space in X value is important if the algorithm needs to to backwards from the start node or needs to extend even further than the end node.
--
-- ## Grid Spacing
--
-- The grid spacing is an important factor as it determines the number of nodes and hence the performance of the algorithm. It should be as large as possible.
-- However, if the value is too large, the algorithm might fail to get a valid path.
--
-- A good estimate of the grid spacing is to set it to be smaller (~ half the size) of the smallest gap you need to path.
--
-- # Valid Neighbours
--
-- The A* algorithm needs to know if a transition from one node to another is allowed or not. By default, hopping from one node to another is always possible.
--
-- ## Line of Sight
--
-- For naval
--
--
-- # Heuristic Cost
--
-- In order to determine the optimal path, the pathfinding algorithm needs to know, how costly it is to go from one node to another.
-- Often, this can simply be determined by the distance between two nodes. Therefore, the default cost function is set to be the 2D distance between two nodes.
--
--
-- # Calculate the Path
--
-- Finally, we have to calculate the path. This is done by the @{ASTAR.GetPath}(*ExcludeStart, ExcludeEnd*) function. This function returns a table of nodes, which
-- describe the optimal path from the start node to the end node.
--
-- By default, the start and end node are include in the table that is returned.
--
-- Note that a valid path must not always exist. So you should check if the function returns *nil*.
--
-- Common reasons that a path cannot be found are:
--
-- * The grid is too small ==> increase grid size, e.g. *BoxHY* and/or *SpaceX* if you use a rectangular grid.
-- * The grid spacing is too large ==> decrease *deltaX* and/or *deltaY*
-- * There simply is no valid path ==> you are screwed :(
--
--
-- # Examples
--
-- ## Strait of Hormuz
--
-- Carrier Group finds its way through the Stait of Hormuz.
--
-- ##
--
--
--
-- @field #ASTAR
ASTAR = {
ClassName = "ASTAR",
Debug = nil,
lid = nil,
nodes = {},
counter = 1,
Nnodes = 0,
ncost = 0,
ncostcache = 0,
nvalid = 0,
nvalidcache = 0,
}
--- Node data.
-- @type ASTAR.Node
-- @field #number id Node id.
-- @field Core.Point#COORDINATE coordinate Coordinate of the node.
-- @field #number surfacetype Surface type.
-- @field #table valid Cached valid/invalid nodes.
-- @field #table cost Cached cost.
--- ASTAR infinity.
-- @field #number INF
ASTAR.INF=1/0
--- ASTAR class version.
-- @field #string version
ASTAR.version="0.4.0"
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO list
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO: Add more valid neighbour functions.
-- TODO: Write docs.
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Constructor
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Create a new ASTAR object.
-- @param #ASTAR self
-- @return #ASTAR self
function ASTAR:New()
-- Inherit everything from INTEL class.
local self=BASE:Inherit(self, BASE:New()) --#ASTAR
self.lid="ASTAR | "
return self
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- User functions
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Set coordinate from where to start.
-- @param #ASTAR self
-- @param Core.Point#COORDINATE Coordinate Start coordinate.
-- @return #ASTAR self
function ASTAR:SetStartCoordinate(Coordinate)
self.startCoord=Coordinate
return self
end
--- Set coordinate where you want to go.
-- @param #ASTAR self
-- @param Core.Point#COORDINATE Coordinate end coordinate.
-- @return #ASTAR self
function ASTAR:SetEndCoordinate(Coordinate)
self.endCoord=Coordinate
return self
end
--- Create a node from a given coordinate.
-- @param #ASTAR self
-- @param Core.Point#COORDINATE Coordinate The coordinate where to create the node.
-- @return #ASTAR.Node The node.
function ASTAR:GetNodeFromCoordinate(Coordinate)
local node={} --#ASTAR.Node
node.coordinate=Coordinate
node.surfacetype=Coordinate:GetSurfaceType()
node.id=self.counter
node.valid={}
node.cost={}
self.counter=self.counter+1
return node
end
--- Add a node to the table of grid nodes.
-- @param #ASTAR self
-- @param #ASTAR.Node Node The node to be added.
-- @return #ASTAR self
function ASTAR:AddNode(Node)
self.nodes[Node.id]=Node
self.Nnodes=self.Nnodes+1
return self
end
--- Add a node to the table of grid nodes specifying its coordinate.
-- @param #ASTAR self
-- @param Core.Point#COORDINATE Coordinate The coordinate where the node is created.
-- @return #ASTAR.Node The node.
function ASTAR:AddNodeFromCoordinate(Coordinate)
local node=self:GetNodeFromCoordinate(Coordinate)
self:AddNode(node)
return node
end
--- Check if the coordinate of a node has is at a valid surface type.
-- @param #ASTAR self
-- @param #ASTAR.Node Node The node to be added.
-- @param #table SurfaceTypes Surface types, for example `{land.SurfaceType.WATER}`. By default all surface types are valid.
-- @return #boolean If true, surface type of node is valid.
function ASTAR:CheckValidSurfaceType(Node, SurfaceTypes)
if SurfaceTypes then
if type(SurfaceTypes)~="table" then
SurfaceTypes={SurfaceTypes}
end
for _,surface in pairs(SurfaceTypes) do
if surface==Node.surfacetype then
return true
end
end
return false
else
return true
end
end
--- Add a function to determine if a neighbour of a node is valid.
-- @param #ASTAR self
-- @param #function NeighbourFunction Function that needs to return *true* for a neighbour to be valid.
-- @param ... Condition function arguments if any.
-- @return #ASTAR self
function ASTAR:SetValidNeighbourFunction(NeighbourFunction, ...)
self.ValidNeighbourFunc=NeighbourFunction
self.ValidNeighbourArg={}
if arg then
self.ValidNeighbourArg=arg
end
return self
end
--- Set valid neighbours to require line of sight between two nodes.
-- @param #ASTAR self
-- @param #number CorridorWidth Width of LoS corridor in meters.
-- @return #ASTAR self
function ASTAR:SetValidNeighbourLoS(CorridorWidth)
self:SetValidNeighbourFunction(ASTAR.LoS, CorridorWidth)
return self
end
--- Set valid neighbours to be in a certain distance.
-- @param #ASTAR self
-- @param #number MaxDistance Max distance between nodes in meters. Default is 2000 m.
-- @return #ASTAR self
function ASTAR:SetValidNeighbourDistance(MaxDistance)
self:SetValidNeighbourFunction(ASTAR.DistMax, MaxDistance)
return self
end
--- Set the function which calculates the "cost" to go from one to another node.
-- The first to arguments of this function are always the two nodes under consideration. But you can add optional arguments.
-- Very often the distance between nodes is a good measure for the cost.
-- @param #ASTAR self
-- @param #function CostFunction Function that returns the "cost".
-- @param ... Condition function arguments if any.
-- @return #ASTAR self
function ASTAR:SetCostFunction(CostFunction, ...)
self.CostFunc=CostFunction
self.CostArg={}
if arg then
self.CostArg=arg
end
return self
end
--- Set heuristic cost to go from one node to another to be their 2D distance.
-- @param #ASTAR self
-- @return #ASTAR self
function ASTAR:SetCostDist2D()
self:SetCostFunction(ASTAR.Dist2D)
return self
end
--- Set heuristic cost to go from one node to another to be their 3D distance.
-- @param #ASTAR self
-- @return #ASTAR self
function ASTAR:SetCostDist3D()
self:SetCostFunction(ASTAR.Dist3D)
return self
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Grid functions
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Create a rectangular grid of nodes between star and end coordinate.
-- The coordinate system is oriented along the line between start and end point.
-- @param #ASTAR self
-- @param #table ValidSurfaceTypes Valid surface types. By default is all surfaces are allowed.
-- @param #number BoxHY Box "height" in meters along the y-coordinate. Default 40000 meters (40 km).
-- @param #number SpaceX Additional space in meters before start and after end coordinate. Default 10000 meters (10 km).
-- @param #number deltaX Increment in the direction of start to end coordinate in meters. Default 2000 meters.
-- @param #number deltaY Increment perpendicular to the direction of start to end coordinate in meters. Default is same as deltaX.
-- @param #boolean MarkGrid If true, create F10 map markers at grid nodes.
-- @return #ASTAR self
function ASTAR:CreateGrid(ValidSurfaceTypes, BoxHY, SpaceX, deltaX, deltaY, MarkGrid)
-- Note that internally
-- x coordinate is z: x-->z Line from start to end
-- y coordinate is x: y-->x Perpendicular
-- Grid length and width.
local Dz=SpaceX or 10000
local Dx=BoxHY and BoxHY/2 or 20000
-- Increments.
local dz=deltaX or 2000
local dx=deltaY or dz
-- Heading from start to end coordinate.
local angle=self.startCoord:HeadingTo(self.endCoord)
--Distance between start and end.
local dist=self.startCoord:Get2DDistance(self.endCoord)+2*Dz
-- Origin of map. Needed to translate back to wanted position.
local co=COORDINATE:New(0, 0, 0)
local do1=co:Get2DDistance(self.startCoord)
local ho1=co:HeadingTo(self.startCoord)
-- Start of grid.
local xmin=-Dx
local zmin=-Dz
-- Number of grid points.
local nz=dist/dz+1
local nx=2*Dx/dx+1
-- Debug info.
local text=string.format("Building grid with nx=%d ny=%d => total=%d nodes", nx, nz, nx*nz)
self:I(self.lid..text)
MESSAGE:New(text, 10, "ASTAR"):ToAllIf(self.Debug)
-- Loop over x and z coordinate to create a 2D grid.
for i=1,nx do
-- x coordinate perpendicular to z.
local x=xmin+dx*(i-1)
for j=1,nz do
-- z coordinate connecting start and end.
local z=zmin+dz*(j-1)
-- Rotate 2D.
local vec3=UTILS.Rotate2D({x=x, y=0, z=z}, angle)
-- Coordinate of the node.
local c=COORDINATE:New(vec3.z, vec3.y, vec3.x):Translate(do1, ho1, true)
-- Create a node at this coordinate.
local node=self:GetNodeFromCoordinate(c)
-- Check if node has valid surface type.
if self:CheckValidSurfaceType(node, ValidSurfaceTypes) then
if MarkGrid then
c:MarkToAll(string.format("i=%d, j=%d surface=%d", i, j, node.surfacetype))
end
-- Add node to grid.
self:AddNode(node)
end
end
end
-- Debug info.
local text=string.format("Done building grid!")
self:I(self.lid..text)
MESSAGE:New(text, 10, "ASTAR"):ToAllIf(self.Debug)
return self
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Valid neighbour functions
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Function to check if two nodes have line of sight (LoS).
-- @param #ASTAR.Node nodeA First node.
-- @param #ASTAR.Node nodeB Other node.
-- @param #number corridor (Optional) Width of corridor in meters.
-- @return #boolean If true, two nodes have LoS.
function ASTAR.LoS(nodeA, nodeB, corridor)
local offset=1
local dx=corridor and corridor/2 or nil
local dy=dx
local cA=nodeA.coordinate:GetVec3()
local cB=nodeB.coordinate:GetVec3()
cA.y=offset
cB.y=offset
local los=land.isVisible(cA, cB)
if los and corridor then
-- Heading from A to B.
local heading=nodeA.coordinate:HeadingTo(nodeB.coordinate)
local Ap=UTILS.VecTranslate(cA, dx, heading+90)
local Bp=UTILS.VecTranslate(cB, dx, heading+90)
los=land.isVisible(Ap, Bp)
if los then
local Am=UTILS.VecTranslate(cA, dx, heading-90)
local Bm=UTILS.VecTranslate(cB, dx, heading-90)
los=land.isVisible(Am, Bm)
end
end
return los
end
--- Function to check if distance between two nodes is less than a threshold distance.
-- @param #ASTAR.Node nodeA First node.
-- @param #ASTAR.Node nodeB Other node.
-- @param #number distmax Max distance in meters. Default is 2000 m.
-- @return #boolean If true, distance between the two nodes is below threshold.
function ASTAR.DistMax(nodeA, nodeB, distmax)
distmax=distmax or 2000
local dist=nodeA.coordinate:Get2DDistance(nodeB.coordinate)
return dist<=distmax
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Heuristic cost functions
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Heuristic cost is given by the 2D distance between the nodes.
-- @param #ASTAR.Node nodeA First node.
-- @param #ASTAR.Node nodeB Other node.
-- @return #number Distance between the two nodes.
function ASTAR.Dist2D(nodeA, nodeB)
return nodeA.coordinate:Get2DDistance(nodeB)
end
--- Heuristic cost is given by the 3D distance between the nodes.
-- @param #ASTAR.Node nodeA First node.
-- @param #ASTAR.Node nodeB Other node.
-- @return #number Distance between the two nodes.
function ASTAR.Dist3D(nodeA, nodeB)
return nodeA.coordinate:Get3DDistance(nodeB.coordinate)
end
--- Heuristic cost is given by the distance between the nodes on road.
-- @param #ASTAR.Node nodeA First node.
-- @param #ASTAR.Node nodeB Other node.
-- @return #number Distance between the two nodes.
function ASTAR.DistRoad(nodeA, nodeB)
local path, dist, gotpath=nodeA.coordinate:GetPathOnRoad(nodeB.coordinate, IncludeEndpoints, Railroad, MarkPath, SmokePath)
if gotpath then
return dist
else
return math.huge
end
return nodeA.coordinate:Get3DDistance(nodeB.coordinate)
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Misc functions
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Find the closest node from a given coordinate.
-- @param #ASTAR self
-- @param Core.Point#COORDINATE Coordinate.
-- @return #ASTAR.Node Cloest node to the coordinate.
-- @return #number Distance to closest node in meters.
function ASTAR:FindClosestNode(Coordinate)
local distMin=math.huge
local closeNode=nil
for _,_node in pairs(self.nodes) do
local node=_node --#ASTAR.Node
local dist=node.coordinate:Get2DDistance(Coordinate)
if dist<distMin then
distMin=dist
closeNode=node
end
end
return closeNode, distMin
end
--- Find the start node.
-- @param #ASTAR self
-- @param #ASTAR.Node Node The node to be added to the nodes table.
-- @return #ASTAR self
function ASTAR:FindStartNode()
local node, dist=self:FindClosestNode(self.startCoord)
self.startNode=node
if dist>1000 then
self:I(self.lid.."Adding start node to node grid!")
self:AddNode(node)
end
return self
end
--- Add a node.
-- @param #ASTAR self
-- @param #ASTAR.Node Node The node to be added to the nodes table.
-- @return #ASTAR self
function ASTAR:FindEndNode()
local node, dist=self:FindClosestNode(self.endCoord)
self.endNode=node
if dist>1000 then
self:I(self.lid.."Adding end node to node grid!")
self:AddNode(node)
end
return self
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Main A* pathfinding function
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- A* pathfinding function. This seaches the path along nodes between start and end nodes/coordinates.
-- @param #ASTAR self
-- @param #boolean ExcludeStartNode If *true*, do not include start node in found path. Default is to include it.
-- @param #boolean ExcludeEndNode If *true*, do not include end node in found path. Default is to include it.
-- @return #table Table of nodes from start to finish.
function ASTAR:GetPath(ExcludeStartNode, ExcludeEndNode)
self:FindStartNode()
self:FindEndNode()
local nodes=self.nodes
local start=self.startNode
local goal=self.endNode
-- Sets.
local openset = {}
local closedset = {}
local came_from = {}
local g_score = {}
local f_score = {}
openset[start.id]=true
local Nopen=1
-- Initial scores.
g_score[start.id]=0
f_score[start.id]=g_score[start.id]+self:_HeuristicCost(start, goal)
-- Set start time.
local T0=timer.getAbsTime()
-- Debug message.
local text=string.format("Starting A* pathfinding with %d Nodes", self.Nnodes)
self:I(self.lid..text)
MESSAGE:New(text, 10, "ASTAR"):ToAllIf(self.Debug)
local Tstart=UTILS.GetOSTime()
-- Loop while we still have an open set.
while Nopen > 0 do
-- Get current node.
local current=self:_LowestFscore(openset, f_score)
-- Check if we are at the end node.
if current.id==goal.id then
local path=self:_UnwindPath({}, came_from, goal)
if not ExcludeEndNode then
table.insert(path, goal)
end
if ExcludeStartNode then
table.remove(path, 1)
end
local Tstop=UTILS.GetOSTime()
local dT=nil
if Tstart and Tstop then
dT=Tstop-Tstart
end
-- Debug message.
local text=string.format("Found path with %d nodes (%d total)", #path, self.Nnodes)
if dT then
text=text..string.format(", OS Time %.6f sec", dT)
end
text=text..string.format(", Nvalid=%d [%d cached]", self.nvalid, self.nvalidcache)
text=text..string.format(", Ncost=%d [%d cached]", self.ncost, self.ncostcache)
self:I(self.lid..text)
MESSAGE:New(text, 60, "ASTAR"):ToAllIf(self.Debug)
return path
end
-- Move Node from open to closed set.
openset[current.id]=nil
Nopen=Nopen-1
closedset[current.id]=true
-- Get neighbour nodes.
local neighbors=self:_NeighbourNodes(current, nodes)
-- Loop over neighbours.
for _,neighbor in pairs(neighbors) do
if self:_NotIn(closedset, neighbor.id) then
local tentative_g_score=g_score[current.id]+self:_DistNodes(current, neighbor)
if self:_NotIn(openset, neighbor.id) or tentative_g_score < g_score[neighbor.id] then
came_from[neighbor]=current
g_score[neighbor.id]=tentative_g_score
f_score[neighbor.id]=g_score[neighbor.id]+self:_HeuristicCost(neighbor, goal)
if self:_NotIn(openset, neighbor.id) then
-- Add to open set.
openset[neighbor.id]=true
Nopen=Nopen+1
end
end
end
end
end
-- Debug message.
local text=string.format("WARNING: Could NOT find valid path!")
self:E(self.lid..text)
MESSAGE:New(text, 60, "ASTAR"):ToAllIf(self.Debug)
return nil -- no valid path
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- A* pathfinding helper functions
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Heuristic "cost" function to go from node A to node B. Default is the distance between the nodes.
-- @param #ASTAR self
-- @param #ASTAR.Node nodeA Node A.
-- @param #ASTAR.Node nodeB Node B.
-- @return #number "Cost" to go from node A to node B.
function ASTAR:_HeuristicCost(nodeA, nodeB)
-- Counter.
self.ncost=self.ncost+1
-- Get chached cost if available.
local cost=nodeA.cost[nodeB.id]
if cost~=nil then
self.ncostcache=self.ncostcache+1
return cost
end
local cost=nil
if self.CostFunc then
cost=self.CostFunc(nodeA, nodeB, unpack(self.CostArg))
else
cost=self:_DistNodes(nodeA, nodeB)
end
nodeA.cost[nodeB.id]=cost
nodeB.cost[nodeA.id]=cost -- Symmetric problem.
return cost
end
--- Check if going from a node to a neighbour is possible.
-- @param #ASTAR self
-- @param #ASTAR.Node node A node.
-- @param #ASTAR.Node neighbor Neighbour node.
-- @return #boolean If true, transition between nodes is possible.
function ASTAR:_IsValidNeighbour(node, neighbor)
-- Counter.
self.nvalid=self.nvalid+1
local valid=node.valid[neighbor.id]
if valid~=nil then
--env.info(string.format("Node %d has valid=%s neighbour %d", node.id, tostring(valid), neighbor.id))
self.nvalidcache=self.nvalidcache+1
return valid
end
local valid=nil
if self.ValidNeighbourFunc then
valid=self.ValidNeighbourFunc(node, neighbor, unpack(self.ValidNeighbourArg))
else
valid=true
end
node.valid[neighbor.id]=valid
neighbor.valid[node.id]=valid -- Symmetric problem.
return valid
end
--- Calculate 2D distance between two nodes.
-- @param #ASTAR self
-- @param #ASTAR.Node nodeA Node A.
-- @param #ASTAR.Node nodeB Node B.
-- @return #number Distance between nodes in meters.
function ASTAR:_DistNodes(nodeA, nodeB)
return nodeA.coordinate:Get2DDistance(nodeB.coordinate)
end
--- Function that calculates the lowest F score.
-- @param #ASTAR self
-- @param #table set The set of nodes IDs.
-- @param #number f_score F score.
-- @return #ASTAR.Node Best node.
function ASTAR:_LowestFscore(set, f_score)
local lowest, bestNode = ASTAR.INF, nil
for nid,node in pairs(set) do
local score=f_score[nid]
if score<lowest then
lowest, bestNode = score, nid
end
end
return self.nodes[bestNode]
end
--- Function to get valid neighbours of a node.
-- @param #ASTAR self
-- @param #ASTAR.Node theNode The node.
-- @param #table nodes Possible neighbours.
-- @param #table Valid neighbour nodes.
function ASTAR:_NeighbourNodes(theNode, nodes)
local neighbors = {}
for _,node in pairs(nodes) do
if theNode.id~=node.id then
local isvalid=self:_IsValidNeighbour(theNode, node)
if isvalid then
table.insert(neighbors, node)
end
end
end
return neighbors
end
--- Function to check if a node is not in a set.
-- @param #ASTAR self
-- @param #table set Set of nodes.
-- @param #ASTAR.Node theNode The node to check.
-- @return #boolean If true, the node is not in the set.
function ASTAR:_NotIn(set, theNode)
return set[theNode]==nil
end
--- Unwind path function.
-- @param #ASTAR self
-- @param #table flat_path Flat path.
-- @param #table map Map.
-- @param #ASTAR.Node current_node The current node.
-- @return #table Unwinded path.
function ASTAR:_UnwindPath( flat_path, map, current_node )
if map [current_node] then
table.insert (flat_path, 1, map[current_node])
return self:_UnwindPath(flat_path, map, map[current_node])
else
return flat_path
end
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------

View File

@ -717,6 +717,22 @@ function BASE:CreateEventCrash( EventTime, Initiator )
world.onEvent( Event ) world.onEvent( Event )
end end
--- Creation of a Crash Event.
-- @param #BASE self
-- @param DCS#Time EventTime The time stamp of the event.
-- @param DCS#Object Initiator The initiating object of the event.
function BASE:CreateEventUnitLost(EventTime, Initiator)
self:F( { EventTime, Initiator } )
local Event = {
id = world.event.S_EVENT_UNIT_LOST,
time = EventTime,
initiator = Initiator,
}
world.onEvent( Event )
end
--- Creation of a Dead Event. --- Creation of a Dead Event.
-- @param #BASE self -- @param #BASE self
-- @param DCS#Time EventTime The time stamp of the event. -- @param DCS#Time EventTime The time stamp of the event.

View File

@ -136,7 +136,7 @@ function DATABASE:New()
self:_RegisterClients() self:_RegisterClients()
self:_RegisterStatics() self:_RegisterStatics()
--self:_RegisterPlayers() --self:_RegisterPlayers()
self:_RegisterAirbases() --self:_RegisterAirbases()
self.UNITS_Position = 0 self.UNITS_Position = 0
@ -1253,7 +1253,7 @@ end
-- @param #DATABASE self -- @param #DATABASE self
-- @param Ops.FlightGroup#FLIGHTGROUP flightgroup -- @param Ops.FlightGroup#FLIGHTGROUP flightgroup
function DATABASE:AddFlightGroup(flightgroup) function DATABASE:AddFlightGroup(flightgroup)
self:I({NewFlightGroup=flightgroup.groupname}) self:T({NewFlightGroup=flightgroup.groupname})
self.FLIGHTGROUPS[flightgroup.groupname]=flightgroup self.FLIGHTGROUPS[flightgroup.groupname]=flightgroup
end end

View File

@ -389,7 +389,7 @@ do -- COORDINATE
-- @return #boolean True if units were found. -- @return #boolean True if units were found.
-- @return #boolean True if statics were found. -- @return #boolean True if statics were found.
-- @return #boolean True if scenery objects were found. -- @return #boolean True if scenery objects were found.
-- @return #table Table of MOOSE @[#Wrapper.Unit#UNIT} objects found. -- @return #table Table of MOOSE @{Wrapper.Unit#UNIT} objects found.
-- @return #table Table of DCS static objects found. -- @return #table Table of DCS static objects found.
-- @return #table Table of DCS scenery objects found. -- @return #table Table of DCS scenery objects found.
function COORDINATE:ScanObjects(radius, scanunits, scanstatics, scanscenery) function COORDINATE:ScanObjects(radius, scanunits, scanstatics, scanscenery)
@ -477,7 +477,7 @@ do -- COORDINATE
end end
for _,scenery in pairs(Scenery) do for _,scenery in pairs(Scenery) do
self:T(string.format("Scan found scenery %s typename=%s", scenery:getName(), scenery:getTypeName())) self:T(string.format("Scan found scenery %s typename=%s", scenery:getName(), scenery:getTypeName()))
SCENERY:Register(scenery:getName(), scenery) --SCENERY:Register(scenery:getName(), scenery)
end end
return gotunits, gotstatics, gotscenery, Units, Statics, Scenery return gotunits, gotstatics, gotscenery, Units, Statics, Scenery
@ -523,6 +523,50 @@ do -- COORDINATE
return umin return umin
end end
--- Scan/find SCENERY objects within a certain radius around the coordinate using the world.searchObjects() DCS API function.
-- @param #COORDINATE self
-- @param #number radius (Optional) Scan radius in meters. Default 100 m.
-- @return table Set of scenery objects.
function COORDINATE:ScanScenery(radius)
local _,_,_,_,_,scenerys=self:ScanObjects(radius, false, false, true)
local set={}
for _,_scenery in pairs(scenerys) do
local scenery=_scenery --DCS#Object
local name=scenery:getName()
local s=SCENERY:Register(name, scenery)
table.insert(set, s)
end
return set
end
--- Find the closest scenery to the COORDINATE within a certain radius.
-- @param #COORDINATE self
-- @param #number radius Scan radius in meters. Default 100 m.
-- @return Wrapper.Scenery#SCENERY The closest scenery or #nil if no object is inside the given radius.
function COORDINATE:FindClosestScenery(radius)
local sceneries=self:ScanScenery(radius)
local umin=nil --Wrapper.Scenery#SCENERY
local dmin=math.huge
for _,_scenery in pairs(sceneries) do
local scenery=_scenery --Wrapper.Scenery#SCENERY
local coordinate=scenery:GetCoordinate()
local d=self:Get2DDistance(coordinate)
if d<dmin then
dmin=d
umin=scenery
end
end
return umin
end
--- Calculate the distance from a reference @{#COORDINATE}. --- Calculate the distance from a reference @{#COORDINATE}.
-- @param #COORDINATE self -- @param #COORDINATE self
@ -774,12 +818,8 @@ do -- COORDINATE
local a={x=TargetCoordinate.x-self.x, y=0, z=TargetCoordinate.z-self.z} local a={x=TargetCoordinate.x-self.x, y=0, z=TargetCoordinate.z-self.z}
return UTILS.VecNorm(a) local norm=UTILS.VecNorm(a)
return norm
--local TargetVec3 = TargetCoordinate:GetVec3()
--local SourceVec3 = self:GetVec3()
--return ( ( TargetVec3.x - SourceVec3.x ) ^ 2 + ( TargetVec3.z - SourceVec3.z ) ^ 2 ) ^ 0.5
end end
--- Returns the temperature in Degrees Celsius. --- Returns the temperature in Degrees Celsius.

View File

@ -11,7 +11,7 @@
-- --
-- ### Author: **funkyfranky** -- ### Author: **funkyfranky**
-- @module Core.Timer -- @module Core.Timer
-- @image CORE_Timer.png -- @image Core_Scheduler.JPG
--- TIMER class. --- TIMER class.
@ -19,6 +19,7 @@
-- @field #string ClassName Name of the class. -- @field #string ClassName Name of the class.
-- @field #string lid Class id string for output to DCS log file. -- @field #string lid Class id string for output to DCS log file.
-- @field #number tid Timer ID returned by the DCS API function. -- @field #number tid Timer ID returned by the DCS API function.
-- @field #number uid Unique ID of the timer.
-- @field #function func Timer function. -- @field #function func Timer function.
-- @field #table para Parameters passed to the timer function. -- @field #table para Parameters passed to the timer function.
-- @field #number Tstart Relative start time in seconds. -- @field #number Tstart Relative start time in seconds.
@ -28,7 +29,7 @@
-- @field #number ncallsMax Max number of function calls. If reached, timer is stopped. -- @field #number ncallsMax Max number of function calls. If reached, timer is stopped.
-- @extends Core.Base#BASE -- @extends Core.Base#BASE
--- *Better three hours too soon than a minute too late.* William Shakespeare --- *Better three hours too soon than a minute too late.* - William Shakespeare
-- --
-- === -- ===
-- --
@ -36,7 +37,7 @@
-- --
-- # The TIMER Concept -- # The TIMER Concept
-- --
-- The TIMER class is the little sister of the SCHEDULER class. It does the same thing but is a bit easier to use and has less overhead. It should be sufficient in many cases. -- The TIMER class is the little sister of the @{Core.Scheduler#SCHEDULER} class. It does the same thing but is a bit easier to use and has less overhead. It should be sufficient in many cases.
-- --
-- It provides an easy interface to the DCS [timer.scheduleFunction](https://wiki.hoggitworld.com/view/DCS_func_scheduleFunction). -- It provides an easy interface to the DCS [timer.scheduleFunction](https://wiki.hoggitworld.com/view/DCS_func_scheduleFunction).
-- --
@ -62,20 +63,20 @@
-- --
-- Note that -- Note that
-- --
-- * if *Tstart* is not specified (*nil*), the first function call happens immediately. -- * if *Tstart* is not specified (*nil*), the first function call happens immediately, i.e. after one millisecond.
-- * if *dT* is not specified (*nil*), the function is called only once. -- * if *dT* is not specified (*nil*), the function is called only once.
-- * if *Duration* is not specified (*nil*), the timer runs forever or until stopped manually or until the max function calls are reached (see below). -- * if *Duration* is not specified (*nil*), the timer runs forever or until stopped manually or until the max function calls are reached (see below).
-- --
-- For example, -- For example,
-- --
-- mytimer:Start(3) -- Will call the function once after 3 seconds. -- mytimer:Start(3) -- Will call the function once after 3 seconds.
-- mytimer:Start(nil, 0.5) -- Will call right now and then every 0.5 sec until all eternaty. -- mytimer:Start(nil, 0.5) -- Will call right now and then every 0.5 sec until all eternity.
-- mytimer:Start(nil, 2.0, 20) -- Will call right now and then every 2.0 sec for 20 sec. -- mytimer:Start(nil, 2.0, 20) -- Will call right now and then every 2.0 sec for 20 sec.
-- mytimer:Start(1.0, nil, 10) -- Does not make sense as the function is only called once anyway. -- mytimer:Start(1.0, nil, 10) -- Does not make sense as the function is only called once anyway.
-- --
-- ## Stopping the Timer -- ## Stopping the Timer
-- --
-- The timer can be stopped manually by the @{#TIMER.Start}(*Delay*) function -- The timer can be stopped manually by the @{#TIMER.Stop}(*Delay*) function
-- --
-- mytimer:Stop() -- mytimer:Stop()
-- --

View File

@ -56,6 +56,7 @@
--- @type ZONE_BASE --- @type ZONE_BASE
-- @field #string ZoneName Name of the zone. -- @field #string ZoneName Name of the zone.
-- @field #number ZoneProbability A value between 0 and 1. 0 = 0% and 1 = 100% probability. -- @field #number ZoneProbability A value between 0 and 1. 0 = 0% and 1 = 100% probability.
-- @field Core.Point#COORDINATE Coordinate object of the zone.
-- @extends Core.Fsm#FSM -- @extends Core.Fsm#FSM
@ -221,22 +222,6 @@ function ZONE_BASE:GetPointVec2()
end end
--- Returns a @{Core.Point#COORDINATE} of the zone.
-- @param #ZONE_BASE self
-- @return Core.Point#COORDINATE The Coordinate of the zone.
function ZONE_BASE:GetCoordinate()
self:F2( self.ZoneName )
local Vec2 = self:GetVec2()
local Coordinate = COORDINATE:NewFromVec2( Vec2 )
self:T2( { Coordinate } )
return Coordinate
end
--- Returns the @{DCS#Vec3} of the zone. --- Returns the @{DCS#Vec3} of the zone.
-- @param #ZONE_BASE self -- @param #ZONE_BASE self
-- @param DCS#Distance Height The height to add to the land height where the center of the zone is located. -- @param DCS#Distance Height The height to add to the land height where the center of the zone is located.
@ -280,11 +265,23 @@ function ZONE_BASE:GetCoordinate( Height ) --R2.1
local Vec3 = self:GetVec3( Height ) local Vec3 = self:GetVec3( Height )
local PointVec3 = COORDINATE:NewFromVec3( Vec3 ) if self.Coordinate then
self:T2( { PointVec3 } ) -- Update coordinates.
self.Coordinate.x=Vec3.x
self.Coordinate.y=Vec3.y
self.Coordinate.z=Vec3.z
return PointVec3 --env.info("FF GetCoordinate NEW for ZONE_BASE "..tostring(self.ZoneName))
else
-- Create a new coordinate object.
self.Coordinate=COORDINATE:NewFromVec3(Vec3)
--env.info("FF GetCoordinate NEW for ZONE_BASE "..tostring(self.ZoneName))
end
return self.Coordinate
end end
@ -433,12 +430,51 @@ ZONE_RADIUS = {
-- @param DCS#Distance Radius The radius of the zone. -- @param DCS#Distance Radius The radius of the zone.
-- @return #ZONE_RADIUS self -- @return #ZONE_RADIUS self
function ZONE_RADIUS:New( ZoneName, Vec2, Radius ) function ZONE_RADIUS:New( ZoneName, Vec2, Radius )
-- Inherit ZONE_BASE.
local self = BASE:Inherit( self, ZONE_BASE:New( ZoneName ) ) -- #ZONE_RADIUS local self = BASE:Inherit( self, ZONE_BASE:New( ZoneName ) ) -- #ZONE_RADIUS
self:F( { ZoneName, Vec2, Radius } ) self:F( { ZoneName, Vec2, Radius } )
self.Radius = Radius self.Radius = Radius
self.Vec2 = Vec2 self.Vec2 = Vec2
--self.Coordinate=COORDINATE:NewFromVec2(Vec2)
return self
end
--- Update zone from a 2D vector.
-- @param #ZONE_RADIUS self
-- @param DCS#Vec2 Vec2 The location of the zone.
-- @param DCS#Distance Radius The radius of the zone.
-- @return #ZONE_RADIUS self
function ZONE_RADIUS:UpdateFromVec2(Vec2, Radius)
-- New center of the zone.
self.Vec2=Vec2
if Radius then
self.Radius=Radius
end
return self
end
--- Update zone from a 2D vector.
-- @param #ZONE_RADIUS self
-- @param DCS#Vec3 Vec3 The location of the zone.
-- @param DCS#Distance Radius The radius of the zone.
-- @return #ZONE_RADIUS self
function ZONE_RADIUS:UpdateFromVec3(Vec3, Radius)
-- New center of the zone.
self.Vec2.x=Vec3.x
self.Vec2.y=Vec3.z
if Radius then
self.Radius=Radius
end
return self return self
end end
@ -1397,21 +1433,27 @@ ZONE_POLYGON_BASE = {
ClassName="ZONE_POLYGON_BASE", ClassName="ZONE_POLYGON_BASE",
} }
--- A points array. --- A 2D points array.
-- @type ZONE_POLYGON_BASE.ListVec2 -- @type ZONE_POLYGON_BASE.ListVec2
-- @list <DCS#Vec2> -- @list <DCS#Vec2> Table of 2D vectors.
--- A 3D points array.
-- @type ZONE_POLYGON_BASE.ListVec3
-- @list <DCS#Vec3> Table of 3D vectors.
--- Constructor to create a ZONE_POLYGON_BASE instance, taking the zone name and an array of @{DCS#Vec2}, forming a polygon. --- Constructor to create a ZONE_POLYGON_BASE instance, taking the zone name and an array of @{DCS#Vec2}, forming a polygon.
-- The @{Wrapper.Group#GROUP} waypoints define the polygon corners. The first and the last point are automatically connected. -- The @{Wrapper.Group#GROUP} waypoints define the polygon corners. The first and the last point are automatically connected.
-- @param #ZONE_POLYGON_BASE self -- @param #ZONE_POLYGON_BASE self
-- @param #string ZoneName Name of the zone. -- @param #string ZoneName Name of the zone.
-- @param #ZONE_POLYGON_BASE.ListVec2 PointsArray An array of @{DCS#Vec2}, forming a polygon.. -- @param #ZONE_POLYGON_BASE.ListVec2 PointsArray An array of @{DCS#Vec2}, forming a polygon.
-- @return #ZONE_POLYGON_BASE self -- @return #ZONE_POLYGON_BASE self
function ZONE_POLYGON_BASE:New( ZoneName, PointsArray ) function ZONE_POLYGON_BASE:New( ZoneName, PointsArray )
-- Inherit ZONE_BASE.
local self = BASE:Inherit( self, ZONE_BASE:New( ZoneName ) ) local self = BASE:Inherit( self, ZONE_BASE:New( ZoneName ) )
self:F( { ZoneName, PointsArray } ) self:F( { ZoneName, PointsArray } )
local i = 0 if PointsArray then
self._.Polygon = {} self._.Polygon = {}
@ -1421,6 +1463,42 @@ function ZONE_POLYGON_BASE:New( ZoneName, PointsArray )
self._.Polygon[i].y = PointsArray[i].y self._.Polygon[i].y = PointsArray[i].y
end end
end
return self
end
--- Update polygon points with an array of @{DCS#Vec2}.
-- @param #ZONE_POLYGON_BASE self
-- @param #ZONE_POLYGON_BASE.ListVec2 Vec2Array An array of @{DCS#Vec2}, forming a polygon.
-- @return #ZONE_POLYGON_BASE self
function ZONE_POLYGON_BASE:UpdateFromVec2(Vec2Array)
self._.Polygon = {}
for i=1,#Vec2Array do
self._.Polygon[i] = {}
self._.Polygon[i].x=Vec2Array[i].x
self._.Polygon[i].y=Vec2Array[i].y
end
return self
end
--- Update polygon points with an array of @{DCS#Vec3}.
-- @param #ZONE_POLYGON_BASE self
-- @param #ZONE_POLYGON_BASE.ListVec3 Vec2Array An array of @{DCS#Vec3}, forming a polygon.
-- @return #ZONE_POLYGON_BASE self
function ZONE_POLYGON_BASE:UpdateFromVec3(Vec3Array)
self._.Polygon = {}
for i=1,#Vec3Array do
self._.Polygon[i] = {}
self._.Polygon[i].x=Vec3Array[i].x
self._.Polygon[i].y=Vec3Array[i].z
end
return self return self
end end

View File

@ -46,6 +46,7 @@
-- @type WAREHOUSE -- @type WAREHOUSE
-- @field #string ClassName Name of the class. -- @field #string ClassName Name of the class.
-- @field #boolean Debug If true, send debug messages to all. -- @field #boolean Debug If true, send debug messages to all.
-- @field #number verbosity Verbosity level.
-- @field #string wid Identifier of the warehouse printed before other output to DCS.log file. -- @field #string wid Identifier of the warehouse printed before other output to DCS.log file.
-- @field #boolean Report If true, send status messages to coalition. -- @field #boolean Report If true, send status messages to coalition.
-- @field Wrapper.Static#STATIC warehouse The phyical warehouse structure. -- @field Wrapper.Static#STATIC warehouse The phyical warehouse structure.
@ -57,6 +58,10 @@
-- @field Core.Point#COORDINATE rail Closest point to warehouse on rail. -- @field Core.Point#COORDINATE rail Closest point to warehouse on rail.
-- @field Core.Zone#ZONE spawnzone Zone in which assets are spawned. -- @field Core.Zone#ZONE spawnzone Zone in which assets are spawned.
-- @field #number uid Unique ID of the warehouse. -- @field #number uid Unique ID of the warehouse.
-- @field #boolean markerOn If true, markers are displayed on the F10 map.
-- @field Wrapper.Marker#MARKER markerWarehouse Marker warehouse.
-- @field Wrapper.Marker#MARKER markerRoad Road connection.
-- @field Wrapper.Marker#MARKER markerRail Rail road connection.
-- @field #number markerid ID of the warehouse marker at the airbase. -- @field #number markerid ID of the warehouse marker at the airbase.
-- @field #number dTstatus Time interval in seconds of updating the warehouse status and processing new events. Default 30 seconds. -- @field #number dTstatus Time interval in seconds of updating the warehouse status and processing new events. Default 30 seconds.
-- @field #number queueid Unit id of each request in the queue. Essentially a running number starting at one and incremented when a new request is added. -- @field #number queueid Unit id of each request in the queue. Essentially a running number starting at one and incremented when a new request is added.
@ -79,7 +84,6 @@
-- @field #number lowfuelthresh Low fuel threshold. Triggers the event AssetLowFuel if for any unit fuel goes below this number. -- @field #number lowfuelthresh Low fuel threshold. Triggers the event AssetLowFuel if for any unit fuel goes below this number.
-- @field #boolean respawnafterdestroyed If true, warehouse is respawned after it was destroyed. Assets are kept. -- @field #boolean respawnafterdestroyed If true, warehouse is respawned after it was destroyed. Assets are kept.
-- @field #number respawndelay Delay before respawn in seconds. -- @field #number respawndelay Delay before respawn in seconds.
-- @field #boolean markerOn If true, markers are displayed on the F10 map.
-- @extends Core.Fsm#FSM -- @extends Core.Fsm#FSM
--- Have your assets at the right place at the right time - or not! --- Have your assets at the right place at the right time - or not!
@ -1548,6 +1552,7 @@
WAREHOUSE = { WAREHOUSE = {
ClassName = "WAREHOUSE", ClassName = "WAREHOUSE",
Debug = false, Debug = false,
verbosity = 0,
lid = nil, lid = nil,
Report = true, Report = true,
warehouse = nil, warehouse = nil,
@ -1559,7 +1564,6 @@ WAREHOUSE = {
rail = nil, rail = nil,
spawnzone = nil, spawnzone = nil,
uid = nil, uid = nil,
markerid = nil,
dTstatus = 30, dTstatus = 30,
queueid = 0, queueid = 0,
stock = {}, stock = {},
@ -1609,6 +1613,7 @@ WAREHOUSE = {
-- @field #boolean iscargo If true, asset is cargo. If false asset is transport. Nil if in stock. -- @field #boolean iscargo If true, asset is cargo. If false asset is transport. Nil if in stock.
-- @field #number rid The request ID of this asset. -- @field #number rid The request ID of this asset.
-- @field #boolean arrived If true, asset arrived at its destination. -- @field #boolean arrived If true, asset arrived at its destination.
-- @field #number damage Damage of asset group in percent.
--- Item of the warehouse queue table. --- Item of the warehouse queue table.
-- @type WAREHOUSE.Queueitem -- @type WAREHOUSE.Queueitem
@ -1829,14 +1834,12 @@ WAREHOUSE.version="1.0.2"
-- @param #string alias (Optional) Alias of the warehouse, i.e. the name it will be called when sending messages etc. Default is the name of the static -- @param #string alias (Optional) Alias of the warehouse, i.e. the name it will be called when sending messages etc. Default is the name of the static
-- @return #WAREHOUSE self -- @return #WAREHOUSE self
function WAREHOUSE:New(warehouse, alias) function WAREHOUSE:New(warehouse, alias)
BASE:T({warehouse=warehouse})
-- Check if just a string was given and convert to static. -- Check if just a string was given and convert to static.
if type(warehouse)=="string" then if type(warehouse)=="string" then
local warehousename=warehouse local warehousename=warehouse
warehouse=UNIT:FindByName(warehousename) warehouse=UNIT:FindByName(warehousename)
if warehouse==nil then if warehouse==nil then
--env.info(string.format("No warehouse unit with name %s found trying static.", tostring(warehousename)))
warehouse=STATIC:FindByName(warehousename, true) warehouse=STATIC:FindByName(warehousename, true)
self.isunit=false self.isunit=false
else else
@ -1889,6 +1892,8 @@ function WAREHOUSE:New(warehouse, alias)
-- Defaults -- Defaults
self:SetMarker(true) self:SetMarker(true)
self:SetReportOff()
--self:SetVerbosityLevel(0)
-- Add warehouse to database. -- Add warehouse to database.
_WAREHOUSEDB.Warehouses[self.uid]=self _WAREHOUSEDB.Warehouses[self.uid]=self
@ -2550,6 +2555,15 @@ function WAREHOUSE:SetStatusUpdate(timeinterval)
return self return self
end end
--- Set verbosity level.
-- @param #WAREHOUSE self
-- @param #number VerbosityLevel Level of output (higher=more). Default 0.
-- @return #WAREHOUSE self
function WAREHOUSE:SetVerbosityLevel(VerbosityLevel)
self.verbosity=VerbosityLevel or 0
return self
end
--- Set a zone where the (ground) assets of the warehouse are spawned once requested. --- Set a zone where the (ground) assets of the warehouse are spawned once requested.
-- @param #WAREHOUSE self -- @param #WAREHOUSE self
-- @param Core.Zone#ZONE zone The spawn zone. -- @param Core.Zone#ZONE zone The spawn zone.
@ -3252,16 +3266,6 @@ function WAREHOUSE:onafterStart(From, Event, To)
-- Save self in static object. Easier to retrieve later. -- Save self in static object. Easier to retrieve later.
self.warehouse:SetState(self.warehouse, "WAREHOUSE", self) self.warehouse:SetState(self.warehouse, "WAREHOUSE", self)
-- THIS! caused aircraft to be spawned and started but they would never begin their route!
-- VERY strange. Need to test more.
--[[
-- Debug mark warehouse & spawn zone.
self.zone:BoundZone(30, self.country)
self.spawnzone:BoundZone(30, self.country)
]]
--self.spawnzone:GetCoordinate():MarkToCoalition(string.format("Warehouse %s spawn zone", self.alias), self:GetCoalition())
-- Get the closest point on road wrt spawnzone of ground assets. -- Get the closest point on road wrt spawnzone of ground assets.
local _road=self.spawnzone:GetCoordinate():GetClosestPointToRoad() local _road=self.spawnzone:GetCoordinate():GetClosestPointToRoad()
if _road and self.road==nil then if _road and self.road==nil then
@ -3371,7 +3375,7 @@ function WAREHOUSE:onafterStop(From, Event, To)
self:_UpdateWarehouseMarkText() self:_UpdateWarehouseMarkText()
-- Clear all pending schedules. -- Clear all pending schedules.
--self.CallScheduler:Clear() self.CallScheduler:Clear()
end end
--- On after "Pause" event. Pauses the warehouse, i.e. no requests are processed. However, new requests and new assets can be added in this state. --- On after "Pause" event. Pauses the warehouse, i.e. no requests are processed. However, new requests and new assets can be added in this state.
@ -3401,6 +3405,9 @@ end
-- @param #string To To state. -- @param #string To To state.
function WAREHOUSE:onafterStatus(From, Event, To) function WAREHOUSE:onafterStatus(From, Event, To)
-- General info.
if self.verbosity>=1 then
local FSMstate=self:GetState() local FSMstate=self:GetState()
local coalition=self:GetCoalitionName() local coalition=self:GetCoalitionName()
@ -3408,6 +3415,7 @@ function WAREHOUSE:onafterStatus(From, Event, To)
-- Info. -- Info.
self:I(self.lid..string.format("State=%s %s [%s]: Assets=%d, Requests: waiting=%d, pending=%d", FSMstate, country, coalition, #self.stock, #self.queue, #self.pending)) self:I(self.lid..string.format("State=%s %s [%s]: Assets=%d, Requests: waiting=%d, pending=%d", FSMstate, country, coalition, #self.stock, #self.queue, #self.pending))
end
-- Check if any pending jobs are done and can be deleted from the queue. -- Check if any pending jobs are done and can be deleted from the queue.
self:_JobDone() self:_JobDone()
@ -3465,6 +3473,8 @@ function WAREHOUSE:_JobDone()
for _,request in pairs(self.pending) do for _,request in pairs(self.pending) do
local request=request --#WAREHOUSE.Pendingitem local request=request --#WAREHOUSE.Pendingitem
if request.born then
-- Count number of cargo groups. -- Count number of cargo groups.
local ncargo=0 local ncargo=0
if request.cargogroupset then if request.cargogroupset then
@ -3513,12 +3523,14 @@ function WAREHOUSE:_JobDone()
--------------- ---------------
-- Info on job. -- Info on job.
if self.verbosity>=1 then
local text=string.format("Warehouse %s: Job on request id=%d for warehouse %s done!\n", self.alias, request.uid, request.warehouse.alias) local text=string.format("Warehouse %s: Job on request id=%d for warehouse %s done!\n", self.alias, request.uid, request.warehouse.alias)
text=text..string.format("- %d of %d assets delivered. Casualties %d.", ncargodelivered, ncargotot, ncargodead) text=text..string.format("- %d of %d assets delivered. Casualties %d.", ncargodelivered, ncargotot, ncargodead)
if request.ntransport>0 then if request.ntransport>0 then
text=text..string.format("\n- %d of %d transports returned home. Casualties %d.", ntransporthome, ntransporttot, ntransportdead) text=text..string.format("\n- %d of %d transports returned home. Casualties %d.", ntransporthome, ntransporttot, ntransportdead)
end end
self:_InfoMessage(text, 20) self:_InfoMessage(text, 20)
end
-- Mark request for deletion. -- Mark request for deletion.
table.insert(done, request) table.insert(done, request)
@ -3567,13 +3579,13 @@ function WAREHOUSE:_JobDone()
-- Debug text. -- Debug text.
local text=string.format("Group %s: speed=%d km/h, onground=%s , airbase=%s, spawnzone=%s ==> ishome=%s", group:GetName(), speed, tostring(onground), airbase, tostring(inspawnzone), tostring(ishome)) local text=string.format("Group %s: speed=%d km/h, onground=%s , airbase=%s, spawnzone=%s ==> ishome=%s", group:GetName(), speed, tostring(onground), airbase, tostring(inspawnzone), tostring(ishome))
self:I(self.lid..text) self:T(self.lid..text)
if ishome then if ishome then
-- Info message. -- Info message.
local text=string.format("Warehouse %s: Transport group arrived back home and no cargo left for request id=%d.\nSending transport group %s back to stock.", self.alias, request.uid, group:GetName()) local text=string.format("Warehouse %s: Transport group arrived back home and no cargo left for request id=%d.\nSending transport group %s back to stock.", self.alias, request.uid, group:GetName())
self:_InfoMessage(text) self:T(self.lid..text)
-- Debug smoke. -- Debug smoke.
if self.Debug then if self.Debug then
@ -3627,7 +3639,7 @@ function WAREHOUSE:_JobDone()
end end
end end
end -- born check
end -- loop over requests end -- loop over requests
-- Remove pending requests if done. -- Remove pending requests if done.
@ -3822,6 +3834,11 @@ function WAREHOUSE:onafterAddAsset(From, Event, To, group, ngroups, forceattribu
asset.iscargo=nil asset.iscargo=nil
asset.arrived=nil asset.arrived=nil
-- Destroy group if it is alive.
if group:IsAlive()==true then
asset.damage=asset.life0-group:GetLife()
end
-- Add asset to stock. -- Add asset to stock.
table.insert(self.stock, asset) table.insert(self.stock, asset)
@ -3865,7 +3882,8 @@ function WAREHOUSE:onafterAddAsset(From, Event, To, group, ngroups, forceattribu
if group:IsAlive()==true then if group:IsAlive()==true then
self:_DebugMessage(string.format("Removing group %s", group:GetName()), 5) self:_DebugMessage(string.format("Removing group %s", group:GetName()), 5)
-- Setting parameter to false, i.e. creating NO dead or remove unit event, seems to not confuse the dispatcher logic. -- Setting parameter to false, i.e. creating NO dead or remove unit event, seems to not confuse the dispatcher logic.
group:Destroy(false) -- TODO: It would be nice, however, to have the remove event.
group:Destroy() --(false)
end end
else else
@ -3991,6 +4009,8 @@ function WAREHOUSE:_RegisterAsset(group, ngroups, forceattribute, forcecargobay,
asset.skill=skill asset.skill=skill
asset.assignment=assignment asset.assignment=assignment
asset.spawned=false asset.spawned=false
asset.life0=group:GetLife0()
asset.damage=0
asset.spawngroupname=string.format("%s_AID-%d", templategroupname, asset.uid) asset.spawngroupname=string.format("%s_AID-%d", templategroupname, asset.uid)
if i==1 then if i==1 then
@ -4262,10 +4282,12 @@ end
function WAREHOUSE:onafterRequest(From, Event, To, Request) function WAREHOUSE:onafterRequest(From, Event, To, Request)
-- Info message. -- Info message.
if self.verbosity>=1 then
local text=string.format("Warehouse %s: Processing request id=%d from warehouse %s.\n", self.alias, Request.uid, Request.warehouse.alias) local text=string.format("Warehouse %s: Processing request id=%d from warehouse %s.\n", self.alias, Request.uid, Request.warehouse.alias)
text=text..string.format("Requested %s assets of %s=%s.\n", tostring(Request.nasset), Request.assetdesc, Request.assetdesc==WAREHOUSE.Descriptor.ASSETLIST and "Asset list" or Request.assetdescval) text=text..string.format("Requested %s assets of %s=%s.\n", tostring(Request.nasset), Request.assetdesc, Request.assetdesc==WAREHOUSE.Descriptor.ASSETLIST and "Asset list" or Request.assetdescval)
text=text..string.format("Transports %s of type %s.", tostring(Request.ntransport), tostring(Request.transporttype)) text=text..string.format("Transports %s of type %s.", tostring(Request.ntransport), tostring(Request.transporttype))
self:_InfoMessage(text, 5) self:_InfoMessage(text, 5)
end
------------------------------------------------------------------------------------------------------------------------------------ ------------------------------------------------------------------------------------------------------------------------------------
-- Cargo assets. -- Cargo assets.
@ -4790,22 +4812,8 @@ function WAREHOUSE:onafterArrived(From, Event, To, group)
group:RouteGroundTo(warehouse:GetCoordinate(), group:GetSpeedMax()*0.3, "Off Road") group:RouteGroundTo(warehouse:GetCoordinate(), group:GetSpeedMax()*0.3, "Off Road")
end end
-- NOTE: This is done in the AddAsset() function. Dont know, why we do it also here.
--[[
if istransport==true then
request.ntransporthome=request.ntransporthome+1
request.transportgroupset:Remove(group:GetName(), true)
self:T2(warehouse.lid..string.format("Transport %d of %s returned home.", request.ntransporthome, tostring(request.ntransport)))
elseif istransport==false then
request.ndelivered=request.ndelivered+1
request.cargogroupset:Remove(self:_GetNameWithOut(group), true)
self:T2(warehouse.lid..string.format("Cargo %d of %s delivered.", request.ndelivered, tostring(request.nasset)))
else
self:E(warehouse.lid..string.format("ERROR: Group %s is neither cargo nor transport!", group:GetName()))
end
]]
-- Move asset from pending queue into new warehouse. -- Move asset from pending queue into new warehouse.
self:T(self.lid.."Asset arrived at warehouse adding in 60 sec")
warehouse:__AddAsset(60, group) warehouse:__AddAsset(60, group)
end end
@ -4820,8 +4828,10 @@ end
function WAREHOUSE:onafterDelivered(From, Event, To, request) function WAREHOUSE:onafterDelivered(From, Event, To, request)
-- Debug info -- Debug info
if self.verbosity>=1 then
local text=string.format("Warehouse %s: All assets delivered to warehouse %s!", self.alias, request.warehouse.alias) local text=string.format("Warehouse %s: All assets delivered to warehouse %s!", self.alias, request.warehouse.alias)
self:_InfoMessage(text, 5) self:_InfoMessage(text, 5)
end
-- Make some noise :) -- Make some noise :)
if self.Debug then if self.Debug then
@ -5150,7 +5160,7 @@ end
-- @param #WAREHOUSE.Pendingitem request The request of the dead asset. -- @param #WAREHOUSE.Pendingitem request The request of the dead asset.
function WAREHOUSE:onafterAssetSpawned(From, Event, To, group, asset, request) function WAREHOUSE:onafterAssetSpawned(From, Event, To, group, asset, request)
local text=string.format("Asset %s from request id=%d was spawned!", asset.spawngroupname, request.uid) local text=string.format("Asset %s from request id=%d was spawned!", asset.spawngroupname, request.uid)
self:I(self.lid..text) self:T(self.lid..text)
-- Sete asset state to spawned. -- Sete asset state to spawned.
asset.spawned=true asset.spawned=true
@ -5161,22 +5171,23 @@ function WAREHOUSE:onafterAssetSpawned(From, Event, To, group, asset, request)
local assetitem=_asset --#WAREHOUSE.Assetitem local assetitem=_asset --#WAREHOUSE.Assetitem
-- Debug info. -- Debug info.
self:I(self.lid..string.format("Asset %s spawned %s as %s", assetitem.templatename, tostring(assetitem.spawned), tostring(assetitem.spawngroupname))) self:T(self.lid..string.format("Asset %s spawned %s as %s", assetitem.templatename, tostring(assetitem.spawned), tostring(assetitem.spawngroupname)))
if assetitem.spawned then if assetitem.spawned then
n=n+1 n=n+1
else else
self:E(self.lid.."FF What?! This should not happen!") -- Now this can happend if multiple groups need to be spawned in one request.
--self:I(self.lid.."FF What?! This should not happen!")
end end
end end
-- Trigger event. -- Trigger event.
if n==request.nasset+request.ntransport then if n==request.nasset+request.ntransport then
self:T3(self.lid..string.format("All assets %d (ncargo=%d + ntransport=%d) of request rid=%d spawned. Calling RequestSpawned", n, request.nasset, request.ntransport, request.uid)) self:T(self.lid..string.format("All assets %d (ncargo=%d + ntransport=%d) of request rid=%d spawned. Calling RequestSpawned", n, request.nasset, request.ntransport, request.uid))
self:RequestSpawned(request, request.cargogroupset, request.transportgroupset) self:RequestSpawned(request, request.cargogroupset, request.transportgroupset)
else else
self:T3(self.lid..string.format("Not all assets %d (ncargo=%d + ntransport=%d) of request rid=%d spawned YET", n, request.nasset, request.ntransport, request.uid)) self:T(self.lid..string.format("Not all assets %d (ncargo=%d + ntransport=%d) of request rid=%d spawned YET", n, request.nasset, request.ntransport, request.uid))
end end
end end
@ -5787,7 +5798,7 @@ function WAREHOUSE:_SpawnAssetPrepareTemplate(asset, alias)
template.lateActivation=false template.lateActivation=false
if asset.missionTask then if asset.missionTask then
self:I(self.lid..string.format("Setting mission task to %s", tostring(asset.missionTask))) self:T(self.lid..string.format("Setting mission task to %s", tostring(asset.missionTask)))
template.task=asset.missionTask template.task=asset.missionTask
end end
@ -6112,8 +6123,13 @@ function WAREHOUSE:_OnEventBirth(EventData)
local asset=self:GetAssetByID(aid) local asset=self:GetAssetByID(aid)
local request=self:GetRequestByID(rid) local request=self:GetRequestByID(rid)
if asset and request then
-- Debug message. -- Debug message.
self:T(self.lid..string.format("Warehouse %s captured event birth of its asset unit %s. spawned=%s", self.alias, EventData.IniUnitName, tostring(asset.spawned))) self:T(self.lid..string.format("Warehouse %s captured event birth of request ID=%d, asset ID=%d, unit %s spawned=%s", self.alias, request.uid, asset.uid, EventData.IniUnitName, tostring(asset.spawned)))
-- Set born to true.
request.born=true
-- Birth is triggered for each unit. We need to make sure not to call this too often! -- Birth is triggered for each unit. We need to make sure not to call this too often!
if not asset.spawned then if not asset.spawned then
@ -6139,10 +6155,15 @@ function WAREHOUSE:_OnEventBirth(EventData)
-- Asset spawned FSM function. -- Asset spawned FSM function.
--self:__AssetSpawned(1, group, asset, request) --self:__AssetSpawned(1, group, asset, request)
--env.info(string.format("FF asset spawned %s, %s", asset.spawngroupname, EventData.IniUnitName))
self:AssetSpawned(group, asset, request) self:AssetSpawned(group, asset, request)
end end
else
self:E(self.lid..string.format("ERROR: Either asset AID=%s or request RID=%s are nil in event birth of unit %s", tostring(aid), tostring(rid), tostring(EventData.IniUnitName)))
end
else else
--self:T3({wid=wid, uid=self.uid, match=(wid==self.uid), tw=type(wid), tu=type(self.uid)}) --self:T3({wid=wid, uid=self.uid, match=(wid==self.uid), tw=type(wid), tu=type(self.uid)})
end end
@ -6260,7 +6281,6 @@ function WAREHOUSE:_OnEventArrived(EventData)
local istransport=self:_GroupIsTransport(group, request) local istransport=self:_GroupIsTransport(group, request)
-- Get closest airbase. -- Get closest airbase.
-- Note, this crashed at somepoint when the Tarawa was in the mission. Don't know why. Deleting the Tarawa and adding it again solved the problem.
local closest=group:GetCoordinate():GetClosestAirbase() local closest=group:GetCoordinate():GetClosestAirbase()
-- Check if engine shutdown happend at right airbase because the event is also triggered in other situations. -- Check if engine shutdown happend at right airbase because the event is also triggered in other situations.
@ -6269,15 +6289,19 @@ function WAREHOUSE:_OnEventArrived(EventData)
-- Check that group is cargo and not transport. -- Check that group is cargo and not transport.
if istransport==false and rightairbase then if istransport==false and rightairbase then
-- Debug info.
local text=string.format("Air asset group %s from warehouse %s arrived at its destination.", group:GetName(), self.alias)
self:_InfoMessage(text)
-- Trigger arrived event for this group. Note that each unit of a group will trigger this event. So the onafterArrived function needs to take care of that. -- Trigger arrived event for this group. Note that each unit of a group will trigger this event. So the onafterArrived function needs to take care of that.
-- Actually, we only take the first unit of the group that arrives. If it does, we assume the whole group arrived, which might not be the case, since -- Actually, we only take the first unit of the group that arrives. If it does, we assume the whole group arrived, which might not be the case, since
-- some units might still be taxiing or whatever. Therefore, we add 10 seconds for each additional unit of the group until the first arrived event is triggered. -- some units might still be taxiing or whatever. Therefore, we add 10 seconds for each additional unit of the group until the first arrived event is triggered.
local nunits=#group:GetUnits() local nunits=#group:GetUnits()
local dt=10*(nunits-1)+1 -- one unit = 1 sec, two units = 11 sec, three units = 21 sec before we call the group arrived. local dt=10*(nunits-1)+1 -- one unit = 1 sec, two units = 11 sec, three units = 21 sec before we call the group arrived.
-- Debug info.
if self.verbosity>=1 then
local text=string.format("Air asset group %s from warehouse %s arrived at its destination. Trigger Arrived event in %d sec", group:GetName(), self.alias, dt)
self:_InfoMessage(text)
end
-- Arrived event.
self:__Arrived(dt, group) self:__Arrived(dt, group)
end end
@ -7497,7 +7521,7 @@ end
function WAREHOUSE:_FindParkingForAssets(airbase, assets) function WAREHOUSE:_FindParkingForAssets(airbase, assets)
-- Init default -- Init default
local scanradius=100 local scanradius=25
local scanunits=true local scanunits=true
local scanstatics=true local scanstatics=true
local scanscenery=false local scanscenery=false
@ -7521,24 +7545,27 @@ function WAREHOUSE:_FindParkingForAssets(airbase, assets)
for i,unit in pairs(units) do for i,unit in pairs(units) do
local coord=COORDINATE:New(unit.x, unit.alt, unit.y) local coord=COORDINATE:New(unit.x, unit.alt, unit.y)
coords[unit.name]=coord coords[unit.name]=coord
--[[
local airbase=coord:GetClosestAirbase()
local _,TermID, dist, spot=coord:GetClosestParkingSpot(airbase)
if dist<=10 then
env.info(string.format("Found client %s on parking spot %d at airbase %s", unit.name, TermID, airbase:GetName()))
end
]]
end end
end end
return coords return coords
end end
-- Get parking spot data table. This contains all free and "non-free" spots. -- Get parking spot data table. This contains all free and "non-free" spots.
local parkingdata=airbase:GetParkingSpotsTable() local parkingdata=airbase.parking --airbase:GetParkingSpotsTable()
---
-- Find all obstacles
---
-- List of obstacles. -- List of obstacles.
local obstacles={} local obstacles={}
-- Check all clients. Clients dont change so we can put that out of the loop.
self.clientcoords=self.clientcoords or _clients()
for clientname,_coord in pairs(self.clientcoords) do
table.insert(obstacles, {coord=_coord, size=15, name=clientname, type="client"})
end
-- Loop over all parking spots and get the currently present obstacles. -- Loop over all parking spots and get the currently present obstacles.
-- How long does this take on very large airbases, i.e. those with hundereds of parking spots? Seems to be okay! -- How long does this take on very large airbases, i.e. those with hundereds of parking spots? Seems to be okay!
for _,parkingspot in pairs(parkingdata) do for _,parkingspot in pairs(parkingdata) do
@ -7553,22 +7580,16 @@ function WAREHOUSE:_FindParkingForAssets(airbase, assets)
-- Check all units. -- Check all units.
for _,_unit in pairs(_units) do for _,_unit in pairs(_units) do
local unit=_unit --Wrapper.Unit#UNIT local unit=_unit --Wrapper.Unit#UNIT
local _coord=unit:GetCoordinate() local _coord=unit:GetVec3()
local _size=self:_GetObjectSize(unit:GetDCSObject()) local _size=self:_GetObjectSize(unit:GetDCSObject())
local _name=unit:GetName() local _name=unit:GetName()
table.insert(obstacles, {coord=_coord, size=_size, name=_name, type="unit"}) table.insert(obstacles, {coord=_coord, size=_size, name=_name, type="unit"})
end end
-- Check all clients.
local clientcoords=_clients()
for clientname,_coord in pairs(clientcoords) do
table.insert(obstacles, {coord=_coord, size=15, name=clientname, type="client"})
end
-- Check all statics. -- Check all statics.
for _,static in pairs(_statics) do for _,static in pairs(_statics) do
local _vec3=static:getPoint() local _coord=static:getPoint()
local _coord=COORDINATE:NewFromVec3(_vec3) --local _coord=COORDINATE:NewFromVec3(_vec3)
local _name=static:getName() local _name=static:getName()
local _size=self:_GetObjectSize(static) local _size=self:_GetObjectSize(static)
table.insert(obstacles, {coord=_coord, size=_size, name=_name, type="static"}) table.insert(obstacles, {coord=_coord, size=_size, name=_name, type="static"})
@ -7576,8 +7597,8 @@ function WAREHOUSE:_FindParkingForAssets(airbase, assets)
-- Check all scenery. -- Check all scenery.
for _,scenery in pairs(_sceneries) do for _,scenery in pairs(_sceneries) do
local _vec3=scenery:getPoint() local _coord=scenery:getPoint()
local _coord=COORDINATE:NewFromVec3(_vec3) --local _coord=COORDINATE:NewFromVec3(_vec3)
local _name=scenery:getTypeName() local _name=scenery:getTypeName()
local _size=self:_GetObjectSize(scenery) local _size=self:_GetObjectSize(scenery)
table.insert(obstacles, {coord=_coord, size=_size, name=_name, type="scenery"}) table.insert(obstacles, {coord=_coord, size=_size, name=_name, type="scenery"})
@ -7585,6 +7606,10 @@ function WAREHOUSE:_FindParkingForAssets(airbase, assets)
end end
---
-- Get Parking Spots
---
-- Parking data for all assets. -- Parking data for all assets.
local parking={} local parking={}
@ -7612,20 +7637,9 @@ function WAREHOUSE:_FindParkingForAssets(airbase, assets)
-- Coordinate of the parking spot. -- Coordinate of the parking spot.
local _spot=parkingspot.Coordinate -- Core.Point#COORDINATE local _spot=parkingspot.Coordinate -- Core.Point#COORDINATE
local _termid=parkingspot.TerminalID local _termid=parkingspot.TerminalID
local _toac=parkingspot.TOAC
--env.info(string.format("FF asset=%s (id=%d): needs terminal type=%d, id=%d, #obstacles=%d", _asset.templatename, _asset.uid, terminaltype, _termid, #obstacles))
local free=true local free=true
local problem=nil local problem=nil
-- Safe parking using TO_AC from DCS result.
self:I(self.lid..string.format("Parking spot %d TOAC=%s (safe park=%s).", _termid, tostring(_toac), tostring(self.safeparking)))
if self.safeparking and _toac then
free=false
self:I(self.lid..string.format("Parking spot %d is occupied by other aircraft taking off (TOAC).", _termid))
end
-- Loop over all obstacles. -- Loop over all obstacles.
for _,obstacle in pairs(obstacles) do for _,obstacle in pairs(obstacles) do
@ -7652,7 +7666,8 @@ function WAREHOUSE:_FindParkingForAssets(airbase, assets)
-- Add parkingspot for this asset unit. -- Add parkingspot for this asset unit.
table.insert(parking[_asset.uid], parkingspot) table.insert(parking[_asset.uid], parkingspot)
self:I(self.lid..string.format("Parking spot %d is free for asset id=%d!", _termid, _asset.uid)) -- Debug
self:T(self.lid..string.format("Parking spot %d is free for asset id=%d!", _termid, _asset.uid))
-- Add the unit as obstacle so that this spot will not be available for the next unit. -- Add the unit as obstacle so that this spot will not be available for the next unit.
table.insert(obstacles, {coord=_spot, size=_asset.size, name=_asset.templatename, type="asset"}) table.insert(obstacles, {coord=_spot, size=_asset.size, name=_asset.templatename, type="asset"})
@ -7663,7 +7678,7 @@ function WAREHOUSE:_FindParkingForAssets(airbase, assets)
else else
-- Debug output for occupied spots. -- Debug output for occupied spots.
self:I(self.lid..string.format("Parking spot %d is occupied or not big enough!", _termid)) self:T(self.lid..string.format("Parking spot %d is occupied or not big enough!", _termid))
if self.Debug then if self.Debug then
local coord=problem.coord --Core.Point#COORDINATE local coord=problem.coord --Core.Point#COORDINATE
local text=string.format("Obstacle blocking spot #%d is %s type %s with size=%.1f m and distance=%.1f m.", _termid, problem.name, problem.type, problem.size, problem.dist) local text=string.format("Obstacle blocking spot #%d is %s type %s with size=%.1f m and distance=%.1f m.", _termid, problem.name, problem.type, problem.size, problem.dist)
@ -8288,6 +8303,8 @@ end
-- @param #string name Name of the queue for info reasons. -- @param #string name Name of the queue for info reasons.
function WAREHOUSE:_PrintQueue(queue, name) function WAREHOUSE:_PrintQueue(queue, name)
if self.verbosity>=2 then
local total="Empty" local total="Empty"
if #queue>0 then if #queue>0 then
total=string.format("Total = %d", #queue) total=string.format("Total = %d", #queue)
@ -8345,17 +8362,19 @@ function WAREHOUSE:_PrintQueue(queue, name)
end end
if #queue==0 then if #queue==0 then
self:T(self.lid..text) self:I(self.lid..text)
else else
if total~="Empty" then if total~="Empty" then
self:I(self.lid..text) self:I(self.lid..text)
end end
end end
end end
end
--- Display status of warehouse. --- Display status of warehouse.
-- @param #WAREHOUSE self -- @param #WAREHOUSE self
function WAREHOUSE:_DisplayStatus() function WAREHOUSE:_DisplayStatus()
if self.verbosity>=3 then
local text=string.format("\n------------------------------------------------------\n") local text=string.format("\n------------------------------------------------------\n")
text=text..string.format("Warehouse %s status: %s\n", self.alias, self:GetState()) text=text..string.format("Warehouse %s status: %s\n", self.alias, self:GetState())
text=text..string.format("------------------------------------------------------\n") text=text..string.format("------------------------------------------------------\n")
@ -8366,7 +8385,8 @@ function WAREHOUSE:_DisplayStatus()
text=text..string.format("Pending requests = %d\n", #self.pending) text=text..string.format("Pending requests = %d\n", #self.pending)
text=text..string.format("------------------------------------------------------\n") text=text..string.format("------------------------------------------------------\n")
text=text..self:_GetStockAssetsText() text=text..self:_GetStockAssetsText()
self:T(text) self:I(text)
end
end end
--- Get text about warehouse stock. --- Get text about warehouse stock.
@ -8406,27 +8426,47 @@ function WAREHOUSE:_UpdateWarehouseMarkText()
if self.markerOn then if self.markerOn then
-- Create a mark with the current assets in stock. -- Marker text.
if self.markerid~=nil then
trigger.action.removeMark(self.markerid)
end
-- Get assets in stock.
local _data=self:GetStockInfo(self.stock)
-- Text.
local text=string.format("Warehouse state: %s\nTotal assets in stock %d:\n", self:GetState(), #self.stock) local text=string.format("Warehouse state: %s\nTotal assets in stock %d:\n", self:GetState(), #self.stock)
for _attribute,_count in pairs(self:GetStockInfo(self.stock) or {}) do
for _attribute,_count in pairs(_data) do
if _count>0 then if _count>0 then
local attribute=tostring(UTILS.Split(_attribute, "_")[2]) local attribute=tostring(UTILS.Split(_attribute, "_")[2])
text=text..string.format("%s=%d, ", attribute,_count) text=text..string.format("%s=%d, ", attribute,_count)
end end
end end
-- Create/update marker at warehouse in F10 map. local coordinate=self:GetCoordinate()
self.markerid=self:GetCoordinate():MarkToCoalition(text, self:GetCoalition(), true) local coalition=self:GetCoalition()
if not self.markerWarehouse then
-- Create a new marker.
self.markerWarehouse=MARKER:New(coordinate, text):ToCoalition(coalition)
else
local refresh=false
if self.markerWarehouse.text~=text then
self.markerWarehouse.text=text
refresh=true
end
if self.markerWarehouse.coordinate~=coordinate then
self.markerWarehouse.coordinate=coordinate
refresh=true
end
if self.markerWarehouse.coalition~=coalition then
self.markerWarehouse.coalition=coalition
refresh=true
end
if refresh then
self.markerWarehouse:Refresh()
end
end
end end
end end
@ -8479,8 +8519,8 @@ end
-- @param #number duration Message display duration in seconds. Default 20 sec. If duration is zero, no message is displayed. -- @param #number duration Message display duration in seconds. Default 20 sec. If duration is zero, no message is displayed.
function WAREHOUSE:_InfoMessage(text, duration) function WAREHOUSE:_InfoMessage(text, duration)
duration=duration or 20 duration=duration or 20
if duration>0 then if duration>0 and self.Debug or self.Report then
MESSAGE:New(text, duration):ToCoalitionIf(self:GetCoalition(), self.Debug or self.Report) MESSAGE:New(text, duration):ToCoalition(self:GetCoalition())
end end
self:I(self.lid..text) self:I(self.lid..text)
end end

View File

@ -15,4 +15,5 @@ _SETTINGS:SetPlayerMenuOn()
_DATABASE:_RegisterCargos() _DATABASE:_RegisterCargos()
_DATABASE:_RegisterZones() _DATABASE:_RegisterZones()
_DATABASE:_RegisterAirbases()

View File

@ -28,6 +28,7 @@ __Moose.Include( 'Scripts/Moose/Core/SpawnStatic.lua' )
__Moose.Include( 'Scripts/Moose/Core/Timer.lua' ) __Moose.Include( 'Scripts/Moose/Core/Timer.lua' )
__Moose.Include( 'Scripts/Moose/Core/Goal.lua' ) __Moose.Include( 'Scripts/Moose/Core/Goal.lua' )
__Moose.Include( 'Scripts/Moose/Core/Spot.lua' ) __Moose.Include( 'Scripts/Moose/Core/Spot.lua' )
__Moose.Include( 'Scripts/Moose/Core/Astar.lua' )
__Moose.Include( 'Scripts/Moose/Wrapper/Object.lua' ) __Moose.Include( 'Scripts/Moose/Wrapper/Object.lua' )
__Moose.Include( 'Scripts/Moose/Wrapper/Identifiable.lua' ) __Moose.Include( 'Scripts/Moose/Wrapper/Identifiable.lua' )
@ -73,9 +74,11 @@ __Moose.Include( 'Scripts/Moose/Ops/RecoveryTanker.lua' )
__Moose.Include( 'Scripts/Moose/Ops/RescueHelo.lua' ) __Moose.Include( 'Scripts/Moose/Ops/RescueHelo.lua' )
__Moose.Include( 'Scripts/Moose/Ops/ATIS.lua' ) __Moose.Include( 'Scripts/Moose/Ops/ATIS.lua' )
__Moose.Include( 'Scripts/Moose/Ops/Auftrag.lua' ) __Moose.Include( 'Scripts/Moose/Ops/Auftrag.lua' )
__Moose.Include( 'Scripts/Moose/Ops/Target.lua' )
__Moose.Include( 'Scripts/Moose/Ops/OpsGroup.lua' ) __Moose.Include( 'Scripts/Moose/Ops/OpsGroup.lua' )
__Moose.Include( 'Scripts/Moose/Ops/FlightGroup.lua' ) __Moose.Include( 'Scripts/Moose/Ops/FlightGroup.lua' )
__Moose.Include( 'Scripts/Moose/Ops/NavyGroup.lua' ) __Moose.Include( 'Scripts/Moose/Ops/NavyGroup.lua' )
__Moose.Include( 'Scripts/Moose/Ops/ArmyGroup.lua' )
__Moose.Include( 'Scripts/Moose/Ops/Squadron.lua' ) __Moose.Include( 'Scripts/Moose/Ops/Squadron.lua' )
__Moose.Include( 'Scripts/Moose/Ops/AirWing.lua' ) __Moose.Include( 'Scripts/Moose/Ops/AirWing.lua' )
__Moose.Include( 'Scripts/Moose/Ops/Intelligence.lua' ) __Moose.Include( 'Scripts/Moose/Ops/Intelligence.lua' )

File diff suppressed because it is too large Load Diff

View File

@ -260,7 +260,7 @@
-- --
-- That being said, this script allows you to use any of the three cases to be used at any time. Or, in other words, *you* need to specify when which case is safe and appropriate. -- That being said, this script allows you to use any of the three cases to be used at any time. Or, in other words, *you* need to specify when which case is safe and appropriate.
-- --
-- This is a lot of responsability. *You* are the boss, but *you* need to make the right decisions or things will go terribly wrong! -- This is a lot of responsibility. *You* are the boss, but *you* need to make the right decisions or things will go terribly wrong!
-- --
-- Recovery windows can be set up via the @{#AIRBOSS.AddRecoveryWindow} function as explained below. With this it is possible to seamlessly (within reason!) switch recovery cases in the same mission. -- Recovery windows can be set up via the @{#AIRBOSS.AddRecoveryWindow} function as explained below. With this it is possible to seamlessly (within reason!) switch recovery cases in the same mission.
-- --
@ -287,7 +287,7 @@
-- --
-- ![Banner Image](..\Presentations\AIRBOSS\Airboss_Case1_Landing.png) -- ![Banner Image](..\Presentations\AIRBOSS\Airboss_Case1_Landing.png)
-- --
-- Once the aircraft reaches the Inital, the landing pattern begins. The important steps of the pattern are shown in the image above. -- Once the aircraft reaches the Initial, the landing pattern begins. The important steps of the pattern are shown in the image above.
-- --
-- --
-- ## CASE III -- ## CASE III
@ -1932,6 +1932,11 @@ function AIRBOSS:New(carriername, alias)
-- Welcome players. -- Welcome players.
self:SetWelcomePlayers(true) self:SetWelcomePlayers(true)
-- Coordinates
self.landingcoord=COORDINATE:New(0,0,0) --Core.Point#COORDINATE
self.sterncoord=COORDINATE:New(0, 0, 0) --Core.Point#COORDINATE
self.landingspotcoord=COORDINATE:New(0,0,0) --Core.Point#COORDINATE
-- Init carrier parameters. -- Init carrier parameters.
if self.carriertype==AIRBOSS.CarrierType.STENNIS then if self.carriertype==AIRBOSS.CarrierType.STENNIS then
self:_InitStennis() self:_InitStennis()
@ -2464,7 +2469,7 @@ function AIRBOSS:AddRecoveryWindow(starttime, stoptime, case, holdingoffset, tur
local Tstart=UTILS.ClockToSeconds(starttime) local Tstart=UTILS.ClockToSeconds(starttime)
-- Set stop time. -- Set stop time.
local Tstop=UTILS.ClockToSeconds(stoptime or Tstart+90*60) local Tstop=stoptime and UTILS.ClockToSeconds(stoptime) or Tstart+90*60
-- Consistancy check for timing. -- Consistancy check for timing.
if Tstart>Tstop then if Tstart>Tstop then
@ -3379,6 +3384,12 @@ function AIRBOSS:onafterStart(From, Event, To)
self:HandleEvent(EVENTS.Ejection) self:HandleEvent(EVENTS.Ejection)
self:HandleEvent(EVENTS.PlayerLeaveUnit, self._PlayerLeft) self:HandleEvent(EVENTS.PlayerLeaveUnit, self._PlayerLeft)
self:HandleEvent(EVENTS.MissionEnd) self:HandleEvent(EVENTS.MissionEnd)
self:HandleEvent(EVENTS.RemoveUnit)
--self.StatusScheduler=SCHEDULER:New(self)
--self.StatusScheduler:Schedule(self, self._Status, {}, 1, 0.5)
self.StatusTimer=TIMER:New(self._Status, self):Start(2, 0.5)
-- Start status check in 1 second. -- Start status check in 1 second.
self:__Status(1) self:__Status(1)
@ -3391,19 +3402,12 @@ end
-- @param #string To To state. -- @param #string To To state.
function AIRBOSS:onafterStatus(From, Event, To) function AIRBOSS:onafterStatus(From, Event, To)
if true then
--env.info("FF Status ==> return")
--return
end
-- Get current time. -- Get current time.
local time=timer.getTime() local time=timer.getTime()
-- Update marshal and pattern queue every 30 seconds. -- Update marshal and pattern queue every 30 seconds.
if time-self.Tqueue>self.dTqueue then if time-self.Tqueue>self.dTqueue then
--collectgarbage()
-- Get time. -- Get time.
local clock=UTILS.SecondsToClock(timer.getAbsTime()) local clock=UTILS.SecondsToClock(timer.getAbsTime())
local eta=UTILS.SecondsToClock(self:_GetETAatNextWP()) local eta=UTILS.SecondsToClock(self:_GetETAatNextWP())
@ -3414,7 +3418,7 @@ function AIRBOSS:onafterStatus(From, Event, To)
local speed=self.carrier:GetVelocityKNOTS() local speed=self.carrier:GetVelocityKNOTS()
-- Check water is ahead. -- Check water is ahead.
local collision=self:_CheckCollisionCoord(pos:Translate(self.collisiondist, hdg)) local collision=false --self:_CheckCollisionCoord(pos:Translate(self.collisiondist, hdg))
local holdtime=0 local holdtime=0
if self.holdtimestamp then if self.holdtimestamp then
@ -3471,15 +3475,9 @@ function AIRBOSS:onafterStatus(From, Event, To)
self.recoverywindow.WIND=false self.recoverywindow.WIND=false
end end
else
-- Find path around the obstacle.
if not self.detour then
--self:_Pathfinder()
end end
end end
end
-- Check recovery times and start/stop recovery mode if necessary. -- Check recovery times and start/stop recovery mode if necessary.
@ -3509,14 +3507,21 @@ function AIRBOSS:onafterStatus(From, Event, To)
self:_ActivateBeacons() self:_ActivateBeacons()
end end
-- Call status every ~0.5 seconds.
self:__Status(-30)
end
--- Check AI status. Pattern queue AI in the groove? Marshal queue AI arrived in holding zone?
-- @param #AIRBOSS self
function AIRBOSS:_Status()
-- Check player status. -- Check player status.
self:_CheckPlayerStatus() self:_CheckPlayerStatus()
-- Check AI landing pattern status -- Check AI landing pattern status
self:_CheckAIStatus() self:_CheckAIStatus()
-- Call status every ~0.5 seconds.
self:__Status(-self.dTstatus)
end end
--- Check AI status. Pattern queue AI in the groove? Marshal queue AI arrived in holding zone? --- Check AI status. Pattern queue AI in the groove? Marshal queue AI arrived in holding zone?
@ -3568,11 +3573,15 @@ function AIRBOSS:_CheckAIStatus()
-- Get lineup and distance to carrier. -- Get lineup and distance to carrier.
local lineup=self:_Lineup(unit, true) local lineup=self:_Lineup(unit, true)
local unitcoord=unit:GetCoord()
local dist=unitcoord:Get2DDistance(self:GetCoord())
-- Distance in NM. -- Distance in NM.
local distance=UTILS.MetersToNM(unit:GetCoordinate():Get2DDistance(self:GetCoordinate())) local distance=UTILS.MetersToNM(dist)
-- Altitude in ft. -- Altitude in ft.
local alt=UTILS.MetersToFeet(unit:GetAltitude()) local alt=UTILS.MetersToFeet(unitcoord.y)
-- Check if parameters are right and flight is in the groove. -- Check if parameters are right and flight is in the groove.
if lineup<2 and distance<=0.75 and alt<500 and not element.ballcall then if lineup<2 and distance<=0.75 and alt<500 and not element.ballcall then
@ -8825,6 +8834,58 @@ function AIRBOSS:OnEventEjection(EventData)
end end
--- Airboss event handler for event REMOVEUNIT.
-- @param #AIRBOSS self
-- @param Core.Event#EVENTDATA EventData
function AIRBOSS:OnEventRemoveUnit(EventData)
self:F3({eventland = EventData})
-- Nil checks.
if EventData==nil then
self:E(self.lid.."ERROR: EventData=nil in event REMOVEUNIT!")
self:E(EventData)
return
end
if EventData.IniUnit==nil then
self:E(self.lid.."ERROR: EventData.IniUnit=nil in event REMOVEUNIT!")
self:E(EventData)
return
end
local _unitName=EventData.IniUnitName
local _unit, _playername=self:_GetPlayerUnitAndName(_unitName)
self:T3(self.lid.."EJECT: unit = "..tostring(EventData.IniUnitName))
self:T3(self.lid.."EJECT: group = "..tostring(EventData.IniGroupName))
self:T3(self.lid.."EJECT: player = "..tostring(_playername))
if _unit and _playername then
self:T(self.lid..string.format("Player %s removed!",_playername))
-- Get player flight.
local flight=self.players[_playername]
-- Remove flight completely from all queues and collapse marshal if necessary.
if flight then
self:_RemoveFlight(flight, true)
end
else
-- Debug message.
self:T(self.lid..string.format("AI unit %s removed!", EventData.IniUnitName))
-- Remove element/unit from flight group and from all queues if no elements alive.
self:_RemoveUnitFromFlight(EventData.IniUnit)
-- What could happen is, that another element has landed (recovered) already and this one crashes.
-- This would mean that the flight would not be deleted from the queue ==> Check if section recovered.
local flight=self:_GetFlightFromGroupInQueue(EventData.IniGroup, self.flights)
self:_CheckSectionRecovered(flight)
end
end
--- Airboss event handler for event player leave unit. --- Airboss event handler for event player leave unit.
-- @param #AIRBOSS self -- @param #AIRBOSS self
-- @param Core.Event#EVENTDATA EventData -- @param Core.Event#EVENTDATA EventData
@ -10287,24 +10348,25 @@ function AIRBOSS:_GetSternCoord()
local FB=self:GetFinalBearing() local FB=self:GetFinalBearing()
-- Stern coordinate (sterndist<0). Also translate 10 meters starboard wrt Final bearing. -- Stern coordinate (sterndist<0). Also translate 10 meters starboard wrt Final bearing.
local stern=self:GetCoordinate() self.sterncoord:UpdateFromCoordinate(self:GetCoordinate())
--local stern=self:GetCoordinate()
-- Stern coordinate (sterndist<0). -- Stern coordinate (sterndist<0).
if self.carriertype==AIRBOSS.CarrierType.TARAWA then if self.carriertype==AIRBOSS.CarrierType.TARAWA then
-- Tarawa: Translate 8 meters port. -- Tarawa: Translate 8 meters port.
stern=stern:Translate(self.carrierparam.sterndist, hdg):Translate(8, FB-90) self.sterncoord:Translate(self.carrierparam.sterndist, hdg, true, true):Translate(8, FB-90, true, true)
elseif self.carriertype==AIRBOSS.CarrierType.STENNIS then elseif self.carriertype==AIRBOSS.CarrierType.STENNIS then
-- Stennis: translate 7 meters starboard wrt Final bearing. -- Stennis: translate 7 meters starboard wrt Final bearing.
stern=stern:Translate(self.carrierparam.sterndist, hdg):Translate(7, FB+90) self.sterncoord:Translate(self.carrierparam.sterndist, hdg, true, true):Translate(7, FB+90, true, true)
else else
-- Nimitz SC: translate 8 meters starboard wrt Final bearing. -- Nimitz SC: translate 8 meters starboard wrt Final bearing.
stern=stern:Translate(self.carrierparam.sterndist, hdg):Translate(8.5, FB+90) self.sterncoord:Translate(self.carrierparam.sterndist, hdg, true, true):Translate(8.5, FB+90, true, true)
end end
-- Set altitude. -- Set altitude.
stern:SetAltitude(self.carrierparam.deckheight) self.sterncoord:SetAltitude(self.carrierparam.deckheight)
return stern return self.sterncoord
end end
--- Get wire from landing position. --- Get wire from landing position.
@ -10504,6 +10566,8 @@ end
-- @return Core.Zone#ZONE_POLYGON_BASE Initial zone. -- @return Core.Zone#ZONE_POLYGON_BASE Initial zone.
function AIRBOSS:_GetZoneInitial(case) function AIRBOSS:_GetZoneInitial(case)
self.zoneInitial=self.zoneInitial or ZONE_POLYGON_BASE:New("Zone CASE I/II Initial")
-- Get radial, i.e. inverse of BRC. -- Get radial, i.e. inverse of BRC.
local radial=self:GetRadial(2, false, false) local radial=self:GetRadial(2, false, false)
@ -10511,7 +10575,7 @@ function AIRBOSS:_GetZoneInitial(case)
local cv=self:GetCoordinate() local cv=self:GetCoordinate()
-- Vec2 array. -- Vec2 array.
local vec2 local vec2={}
if case==1 then if case==1 then
-- Case I -- Case I
@ -10542,9 +10606,12 @@ function AIRBOSS:_GetZoneInitial(case)
end end
-- Polygon zone. -- Polygon zone.
local zone=ZONE_POLYGON_BASE:New("Zone CASE I/II Initial", vec2) --local zone=ZONE_POLYGON_BASE:New("Zone CASE I/II Initial", vec2)
return zone self.zoneInitial:UpdateFromVec2(vec2)
--return zone
return self.zoneInitial
end end
--- Get lineup groove zone. --- Get lineup groove zone.
@ -10552,6 +10619,8 @@ end
-- @return Core.Zone#ZONE_POLYGON_BASE Lineup zone. -- @return Core.Zone#ZONE_POLYGON_BASE Lineup zone.
function AIRBOSS:_GetZoneLineup() function AIRBOSS:_GetZoneLineup()
self.zoneLineup=self.zoneLineup or ZONE_POLYGON_BASE:New("Zone Lineup")
-- Get radial, i.e. inverse of BRC. -- Get radial, i.e. inverse of BRC.
local fbi=self:GetRadial(1, false, false) local fbi=self:GetRadial(1, false, false)
@ -10568,10 +10637,13 @@ function AIRBOSS:_GetZoneLineup()
-- Vec2 array. -- Vec2 array.
local vec2={c1:GetVec2(), c2:GetVec2(), c3:GetVec2(), c4:GetVec2(), c5:GetVec2()} local vec2={c1:GetVec2(), c2:GetVec2(), c3:GetVec2(), c4:GetVec2(), c5:GetVec2()}
-- Polygon zone. self.zoneLineup:UpdateFromVec2(vec2)
local zone=ZONE_POLYGON_BASE:New("Zone Lineup", vec2)
return zone -- Polygon zone.
--local zone=ZONE_POLYGON_BASE:New("Zone Lineup", vec2)
--return zone
return self.zoneLineup
end end
@ -10583,6 +10655,8 @@ end
-- @return Core.Zone#ZONE_POLYGON_BASE Groove zone. -- @return Core.Zone#ZONE_POLYGON_BASE Groove zone.
function AIRBOSS:_GetZoneGroove(l, w, b) function AIRBOSS:_GetZoneGroove(l, w, b)
self.zoneGroove=self.zoneGroove or ZONE_POLYGON_BASE:New("Zone Groove")
l=l or 1.50 l=l or 1.50
w=w or 0.25 w=w or 0.25
b=b or 0.10 b=b or 0.10
@ -10604,10 +10678,13 @@ function AIRBOSS:_GetZoneGroove(l, w, b)
-- Vec2 array. -- Vec2 array.
local vec2={c1:GetVec2(), c2:GetVec2(), c3:GetVec2(), c4:GetVec2(), c5:GetVec2(), c6:GetVec2()} local vec2={c1:GetVec2(), c2:GetVec2(), c3:GetVec2(), c4:GetVec2(), c5:GetVec2(), c6:GetVec2()}
-- Polygon zone. self.zoneGroove:UpdateFromVec2(vec2)
local zone=ZONE_POLYGON_BASE:New("Zone Groove", vec2)
return zone -- Polygon zone.
--local zone=ZONE_POLYGON_BASE:New("Zone Groove", vec2)
--return zone
return self.zoneGroove
end end
--- Get Bullseye zone with radius 1 NM and DME 3 NM from the carrier. Radial depends on recovery case. --- Get Bullseye zone with radius 1 NM and DME 3 NM from the carrier. Radial depends on recovery case.
@ -10631,8 +10708,9 @@ function AIRBOSS:_GetZoneBullseye(case)
-- Create zone. -- Create zone.
local zone=ZONE_RADIUS:New("Zone Bullseye", vec2, radius) local zone=ZONE_RADIUS:New("Zone Bullseye", vec2, radius)
return zone return zone
--self.zoneBullseye=self.zoneBullseye or ZONE_RADIUS:New("Zone Bullseye", vec2, radius)
end end
--- Get dirty up zone with radius 1 NM and DME 9 NM from the carrier. Radial depends on recovery case. --- Get dirty up zone with radius 1 NM and DME 9 NM from the carrier. Radial depends on recovery case.
@ -10828,6 +10906,8 @@ end
-- @return Core.Zone#ZONE Zone surrounding the carrier. -- @return Core.Zone#ZONE Zone surrounding the carrier.
function AIRBOSS:_GetZoneCarrierBox() function AIRBOSS:_GetZoneCarrierBox()
self.zoneCarrierbox=self.zoneCarrierbox or ZONE_POLYGON_BASE:New("Carrier Box Zone")
-- Stern coordinate. -- Stern coordinate.
local S=self:_GetSternCoord() local S=self:_GetSternCoord()
@ -10856,9 +10936,12 @@ function AIRBOSS:_GetZoneCarrierBox()
end end
-- Create polygon zone. -- Create polygon zone.
local zone=ZONE_POLYGON_BASE:New("Carrier Box Zone", vec2) --local zone=ZONE_POLYGON_BASE:New("Carrier Box Zone", vec2)
--return zone
return zone self.zoneCarrierbox:UpdateFromVec2(vec2)
return self.zoneCarrierbox
end end
--- Get zone of landing runway. --- Get zone of landing runway.
@ -10866,6 +10949,8 @@ end
-- @return Core.Zone#ZONE_POLYGON Zone surrounding landing runway. -- @return Core.Zone#ZONE_POLYGON Zone surrounding landing runway.
function AIRBOSS:_GetZoneRunwayBox() function AIRBOSS:_GetZoneRunwayBox()
self.zoneRunwaybox=self.zoneRunwaybox or ZONE_POLYGON_BASE:New("Landing Runway Zone")
-- Stern coordinate. -- Stern coordinate.
local S=self:_GetSternCoord() local S=self:_GetSternCoord()
@ -10888,9 +10973,12 @@ function AIRBOSS:_GetZoneRunwayBox()
end end
-- Create polygon zone. -- Create polygon zone.
local zone=ZONE_POLYGON_BASE:New("Landing Runway Zone", vec2) --local zone=ZONE_POLYGON_BASE:New("Landing Runway Zone", vec2)
--return zone
return zone self.zoneRunwaybox:UpdateFromVec2(vec2)
return self.zoneRunwaybox
end end
@ -10993,12 +11081,14 @@ function AIRBOSS:_GetZoneHolding(case, stack)
-- Post 2.5 NM port of carrier. -- Post 2.5 NM port of carrier.
local Post=self:GetCoordinate():Translate(D, hdg+270) local Post=self:GetCoordinate():Translate(D, hdg+270)
--TODO: update zone not creating a new one.
-- Create holding zone. -- Create holding zone.
zoneHolding=ZONE_RADIUS:New("CASE I Holding Zone", Post:GetVec2(), self.marshalradius) self.zoneHolding=ZONE_RADIUS:New("CASE I Holding Zone", Post:GetVec2(), self.marshalradius)
-- Delta pattern. -- Delta pattern.
if self.carriertype==AIRBOSS.CarrierType.TARAWA then if self.carriertype==AIRBOSS.CarrierType.TARAWA then
zoneHolding=ZONE_RADIUS:New("CASE I Holding Zone", self.carrier:GetVec2(), UTILS.NMToMeters(5)) self.zoneHolding=ZONE_RADIUS:New("CASE I Holding Zone", self.carrier:GetVec2(), UTILS.NMToMeters(5))
end end
@ -11017,10 +11107,12 @@ function AIRBOSS:_GetZoneHolding(case, stack)
-- Square zone length=7NM width=6 NM behind the carrier starting at angels+15 NM behind the carrier. -- Square zone length=7NM width=6 NM behind the carrier starting at angels+15 NM behind the carrier.
-- So stay 0-5 NM (+1 NM error margin) port of carrier. -- So stay 0-5 NM (+1 NM error margin) port of carrier.
zoneHolding=ZONE_POLYGON_BASE:New("CASE II/III Holding Zone", p) self.zoneHolding=self.zoneHolding or ZONE_POLYGON_BASE:New("CASE II/III Holding Zone")
self.zoneHolding:UpdateFromVec2(p)
end end
return zoneHolding return self.zoneHolding
end end
--- Get zone where player are automatically commence when enter. --- Get zone where player are automatically commence when enter.
@ -11061,7 +11153,9 @@ function AIRBOSS:_GetZoneCommence(case, stack)
end end
-- Create holding zone. -- Create holding zone.
zone=ZONE_RADIUS:New("CASE I Commence Zone", Three:GetVec2(), R) self.zoneCommence=self.zoneCommence or ZONE_RADIUS:New("CASE I Commence Zone")
self.zoneCommence:UpdateFromVec2(Three:GetVec2(), R)
else else
-- Case II/III -- Case II/III
@ -11092,11 +11186,13 @@ function AIRBOSS:_GetZoneCommence(case, stack)
end end
-- Zone polygon. -- Zone polygon.
zone=ZONE_POLYGON_BASE:New("CASE II/III Commence Zone", p) self.zoneCommence=self.zoneCommence or ZONE_POLYGON_BASE:New("CASE II/III Commence Zone")
self.zoneCommence:UpdateFromVec2(p)
end end
return zone return self.zoneCommence
end end
---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
@ -11340,8 +11436,11 @@ end
-- @return Core.Point#COORDINATE Optimal landing coordinate. -- @return Core.Point#COORDINATE Optimal landing coordinate.
function AIRBOSS:_GetOptLandingCoordinate() function AIRBOSS:_GetOptLandingCoordinate()
-- Start with stern coordiante.
self.landingcoord:UpdateFromCoordinate(self:_GetSternCoord())
-- Stern coordinate. -- Stern coordinate.
local stern=self:_GetSternCoord() --local stern=self:_GetSternCoord()
-- Final bearing. -- Final bearing.
local FB=self:GetFinalBearing(false) local FB=self:GetFinalBearing(false)
@ -11349,10 +11448,11 @@ function AIRBOSS:_GetOptLandingCoordinate()
if self.carriertype==AIRBOSS.CarrierType.TARAWA then if self.carriertype==AIRBOSS.CarrierType.TARAWA then
-- Landing 100 ft abeam, 120 ft alt. -- Landing 100 ft abeam, 120 ft alt.
stern=self:_GetLandingSpotCoordinate():Translate(35, FB-90) self.landingcoord:UpdateFromCoordinate(self:_GetLandingSpotCoordinate()):Translate(35, FB-90, true, true)
--stern=self:_GetLandingSpotCoordinate():Translate(35, FB-90)
-- Alitude 120 ft. -- Alitude 120 ft.
stern:SetAltitude(UTILS.FeetToMeters(120)) self.landingcoord:SetAltitude(UTILS.FeetToMeters(120))
else else
@ -11360,15 +11460,15 @@ function AIRBOSS:_GetOptLandingCoordinate()
if self.carrierparam.wire3 then if self.carrierparam.wire3 then
-- We take the position of the 3rd wire to approximately account for the length of the aircraft. -- We take the position of the 3rd wire to approximately account for the length of the aircraft.
local w3=self.carrierparam.wire3 local w3=self.carrierparam.wire3
stern=stern:Translate(w3, FB, true) self.landingcoord:Translate(w3, FB, true, true)
end end
-- Add 2 meters to account for aircraft height. -- Add 2 meters to account for aircraft height.
stern.y=stern.y+2 self.landingcoord.y=self.landingcoord.y+2
end end
return stern return self.landingcoord
end end
--- Get landing spot on Tarawa. --- Get landing spot on Tarawa.
@ -11376,8 +11476,10 @@ end
-- @return Core.Point#COORDINATE Primary landing spot coordinate. -- @return Core.Point#COORDINATE Primary landing spot coordinate.
function AIRBOSS:_GetLandingSpotCoordinate() function AIRBOSS:_GetLandingSpotCoordinate()
self.landingspotcoord:UpdateFromCoordinate(self:_GetSternCoord())
-- Stern coordinate. -- Stern coordinate.
local stern=self:_GetSternCoord() --local stern=self:_GetSternCoord()
if self.carriertype==AIRBOSS.CarrierType.TARAWA then if self.carriertype==AIRBOSS.CarrierType.TARAWA then
@ -11385,11 +11487,11 @@ function AIRBOSS:_GetLandingSpotCoordinate()
local hdg=self:GetHeading() local hdg=self:GetHeading()
-- Primary landing spot 7.5 -- Primary landing spot 7.5
stern=stern:Translate(57, hdg):SetAltitude(self.carrierparam.deckheight) self.landingspotcoord:Translate(57, hdg, true, true):SetAltitude(self.carrierparam.deckheight)
end end
return stern return self.landingspotcoord
end end
--- Get true (or magnetic) heading of carrier. --- Get true (or magnetic) heading of carrier.
@ -14333,9 +14435,15 @@ end
-- @param #AIRBOSS self -- @param #AIRBOSS self
-- @return Core.Point#COORDINATE Carrier coordinate. -- @return Core.Point#COORDINATE Carrier coordinate.
function AIRBOSS:GetCoordinate() function AIRBOSS:GetCoordinate()
return self.carrier:GetCoordinate() return self.carrier:GetCoord()
end end
--- Get carrier coordinate.
-- @param #AIRBOSS self
-- @return Core.Point#COORDINATE Carrier coordinate.
function AIRBOSS:GetCoord()
return self.carrier:GetCoord()
end
--- Get static weather of this mission from env.mission.weather. --- Get static weather of this mission from env.mission.weather.
-- @param #AIRBOSS self -- @param #AIRBOSS self

View File

@ -0,0 +1,838 @@
--- **Ops** - Enhanced Ground Group.
--
-- **Main Features:**
--
-- * Dynamically add and remove waypoints.
--
-- ===
--
-- ### Author: **funkyfranky**
-- @module Ops.ArmyGroup
-- @image OPS_ArmyGroup.png
--- ARMYGROUP class.
-- @type ARMYGROUP
-- @field #boolean adinfinitum Resume route at first waypoint when final waypoint is reached.
-- @field #boolean formationPerma Formation that is used permanently and overrules waypoint formations.
-- @extends Ops.OpsGroup#OPSGROUP
--- *Your soul may belong to Jesus, but your ass belongs to the marines.* -- Eugene B. Sledge
--
-- ===
--
-- ![Banner Image](..\Presentations\OPS\ArmyGroup\_Main.png)
--
-- # The ARMYGROUP Concept
--
-- This class enhances naval groups.
--
-- @field #ARMYGROUP
ARMYGROUP = {
ClassName = "ARMYGROUP",
formationPerma = nil,
}
--- Army group element.
-- @type ARMYGROUP.Element
-- @field #string name Name of the element, i.e. the unit.
-- @field #string typename Type name.
--- Army Group version.
-- @field #string version
ARMYGROUP.version="0.1.0"
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO list
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO: A lot.
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Constructor
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Create a new ARMYGROUP class object.
-- @param #ARMYGROUP self
-- @param #string GroupName Name of the group.
-- @return #ARMYGROUP self
function ARMYGROUP:New(GroupName)
-- Inherit everything from FSM class.
local self=BASE:Inherit(self, OPSGROUP:New(GroupName)) -- #ARMYGROUP
-- Set some string id for output to DCS.log file.
self.lid=string.format("ARMYGROUP %s | ", self.groupname)
-- Defaults
self:SetDefaultROE()
self:SetDefaultAlarmstate()
self:SetDetection()
self:SetPatrolAdInfinitum(false)
-- Add FSM transitions.
-- From State --> Event --> To State
self:AddTransition("*", "FullStop", "Holding") -- Hold position.
self:AddTransition("*", "Cruise", "Cruising") -- Hold position.
self:AddTransition("*", "Detour", "OnDetour") -- Make a detour to a coordinate and resume route afterwards.
self:AddTransition("OnDetour", "DetourReached", "Cruising") -- Group reached the detour coordinate.
------------------------
--- Pseudo Functions ---
------------------------
--- Triggers the FSM event "Stop". Stops the ARMYGROUP and all its event handlers.
-- @param #ARMYGROUP self
--- Triggers the FSM event "Stop" after a delay. Stops the ARMYGROUP and all its event handlers.
-- @function [parent=#ARMYGROUP] __Stop
-- @param #ARMYGROUP self
-- @param #number delay Delay in seconds.
-- TODO: Add pseudo functions.
-- Init waypoints.
self:InitWaypoints()
-- Initialize the group.
self:_InitGroup()
-- Handle events:
self:HandleEvent(EVENTS.Birth, self.OnEventBirth)
self:HandleEvent(EVENTS.Dead, self.OnEventDead)
self:HandleEvent(EVENTS.RemoveUnit, self.OnEventRemoveUnit)
-- Start the status monitoring.
self:__Status(-1)
-- Start queue update timer.
self.timerQueueUpdate=TIMER:New(self._QueueUpdate, self):Start(2, 5)
-- Start check zone timer.
self.timerCheckZone=TIMER:New(self._CheckInZones, self):Start(2, 30)
return self
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- User Functions
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Group patrols ad inifintum. If the last waypoint is reached, it will go to waypoint one and repeat its route.
-- @param #ARMYGROUP self
-- @param #boolean switch If true or nil, patrol until the end of time. If false, go along the waypoints once and stop.
-- @return #ARMYGROUP self
function ARMYGROUP:SetPatrolAdInfinitum(switch)
if switch==false then
self.adinfinitum=false
else
self.adinfinitum=true
end
return self
end
--- Get coordinate of the closest road.
-- @param #ARMYGROUP self
-- @return Core.Point#COORDINATE Coordinate of a road closest to the group.
function ARMYGROUP:GetClosestRoad()
return self:GetCoordinate():GetClosestPointToRoad()
end
--- Add a *scheduled* task to fire at a given coordinate.
-- @param #ARMYGROUP self
-- @param Core.Point#COORDINATE Coordinate Coordinate of the target.
-- @param #string Clock Time when to start the attack.
-- @param #number Radius Radius in meters. Default 100 m.
-- @param #number Nshots Number of shots to fire. Default 3.
-- @param #number WeaponType Type of weapon. Default auto.
-- @param #number Prio Priority of the task.
-- @return Ops.OpsGroup#OPSGROUP.Task The task table.
function ARMYGROUP:AddTaskFireAtPoint(Coordinate, Clock, Radius, Nshots, WeaponType, Prio)
local DCStask=CONTROLLABLE.TaskFireAtPoint(nil, Coordinate:GetVec2(), Radius, Nshots, WeaponType)
local task=self:AddTask(DCStask, Clock, nil, Prio)
return task
end
--- Add a *waypoint* task to fire at a given coordinate.
-- @param #ARMYGROUP self
-- @param Core.Point#COORDINATE Coordinate Coordinate of the target.
-- @param Ops.OpsGroup#OPSGROUP.Waypoint Waypoint Where the task is executed. Default is next waypoint.
-- @param #number Radius Radius in meters. Default 100 m.
-- @param #number Nshots Number of shots to fire. Default 3.
-- @param #number WeaponType Type of weapon. Default auto.
-- @param #number Prio Priority of the task.
function ARMYGROUP:AddTaskWaypointFireAtPoint(Coordinate, Waypoint, Radius, Nshots, WeaponType, Prio)
Waypoint=Waypoint or self:GetWaypointNext()
local DCStask=CONTROLLABLE.TaskFireAtPoint(nil, Coordinate:GetVec2(), Radius, Nshots, WeaponType)
self:AddTaskWaypoint(DCStask, Waypoint, nil, Prio)
end
--- Add a *scheduled* task.
-- @param #ARMYGROUP self
-- @param Wrapper.Group#GROUP TargetGroup Target group.
-- @param #number WeaponExpend How much weapons does are used.
-- @param #number WeaponType Type of weapon. Default auto.
-- @param #string Clock Time when to start the attack.
-- @param #number Prio Priority of the task.
function ARMYGROUP:AddTaskAttackGroup(TargetGroup, WeaponExpend, WeaponType, Clock, Prio)
local DCStask=CONTROLLABLE.TaskAttackGroup(nil, TargetGroup, WeaponType, WeaponExpend, AttackQty, Direction, Altitude, AttackQtyLimit, GroupAttack)
self:AddTask(DCStask, Clock, nil, Prio)
end
--- Check if the group is currently holding its positon.
-- @param #ARMYGROUP self
-- @return #boolean If true, group was ordered to hold.
function ARMYGROUP:IsHolding()
return self:Is("Holding")
end
--- Check if the group is currently cruising.
-- @param #ARMYGROUP self
-- @return #boolean If true, group cruising.
function ARMYGROUP:IsCruising()
return self:Is("Cruising")
end
--- Check if the group is currently on a detour.
-- @param #ARMYGROUP self
-- @return #boolean If true, group is on a detour
function ARMYGROUP:IsOnDetour()
return self:Is("OnDetour")
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Status
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
---- Update status.
-- @param #ARMYGROUP self
function ARMYGROUP:onbeforeStatus(From, Event, To)
if self:IsDead() then
self:T(self.lid..string.format("Onbefore Status DEAD ==> false"))
return false
elseif self:IsStopped() then
self:T(self.lid..string.format("Onbefore Status STOPPED ==> false"))
return false
end
return true
end
--- Update status.
-- @param #ARMYGROUP self
function ARMYGROUP:onafterStatus(From, Event, To)
-- FSM state.
local fsmstate=self:GetState()
if self:IsAlive() then
---
-- Detection
---
-- Check if group has detected any units.
if self.detectionOn then
self:_CheckDetectedUnits()
end
-- Update position etc.
self:_UpdatePosition()
-- Check if group got stuck.
self:_CheckStuck()
if self.verbose>=1 then
-- Get number of tasks and missions.
local nTaskTot, nTaskSched, nTaskWP=self:CountRemainingTasks()
local nMissions=self:CountRemainingMissison()
local roe=self:GetROE()
local alarm=self:GetAlarmstate()
local speed=UTILS.MpsToKnots(self.velocity)
local speedEx=UTILS.MpsToKnots(self:GetExpectedSpeed())
local formation=self.option.Formation
-- Info text.
local text=string.format("%s: Wp=%d/%d-->%d Speed=%.1f (%d) Heading=%03d ROE=%d Alarm=%d Formation=%s Tasks=%d Missions=%d",
fsmstate, self.currentwp, #self.waypoints, self:GetWaypointIndexNext(), speed, speedEx, self.heading, roe, alarm, formation, nTaskTot, nMissions)
self:I(self.lid..text)
end
else
-- Info text.
local text=string.format("State %s: Alive=%s", fsmstate, tostring(self:IsAlive()))
self:T2(self.lid..text)
end
---
-- Tasks & Missions
---
self:_PrintTaskAndMissionStatus()
-- Next status update.
self:__Status(-30)
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- FSM Events
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- On after "ElementSpawned" event.
-- @param #ARMYGROUP self
-- @param #string From From state.
-- @param #string Event Event.
-- @param #string To To state.
-- @param #ARMYGROUP.Element Element The group element.
function ARMYGROUP:onafterElementSpawned(From, Event, To, Element)
self:T(self.lid..string.format("Element spawned %s", Element.name))
-- Set element status.
self:_UpdateStatus(Element, OPSGROUP.ElementStatus.SPAWNED)
end
--- On after "Spawned" event.
-- @param #ARMYGROUP self
-- @param #string From From state.
-- @param #string Event Event.
-- @param #string To To state.
function ARMYGROUP:onafterSpawned(From, Event, To)
self:T(self.lid..string.format("Group spawned!"))
-- Update position.
self:_UpdatePosition()
if self.ai then
-- Set default ROE.
self:SwitchROE(self.option.ROE)
-- Set default Alarm State.
self:SwitchAlarmstate(self.option.Alarm)
-- Set TACAN to default.
self:_SwitchTACAN()
-- Turn on the radio.
if self.radioDefault then
self:SwitchRadio(self.radioDefault.Freq, self.radioDefault.Modu)
else
self:SetDefaultRadio(self.radio.Freq, self.radio.Modu, true)
end
end
-- Update route.
self:Cruise()
end
--- On after "UpdateRoute" event.
-- @param #ARMYGROUP self
-- @param #string From From state.
-- @param #string Event Event.
-- @param #string To To state.
-- @param #number n Waypoint number. Default is next waypoint.
-- @param #number Speed Speed in knots. Default cruise speed.
-- @param #number Formation Formation of the group.
function ARMYGROUP:onafterUpdateRoute(From, Event, To, n, Speed, Formation)
-- Update route from this waypoint number onwards.
n=n or self:GetWaypointIndexNext(self.adinfinitum)
-- Update waypoint tasks, i.e. inject WP tasks into waypoint table.
self:_UpdateWaypointTasks(n)
-- Waypoints.
local waypoints={}
-- Total number of waypoints
local N=#self.waypoints
-- Add remaining waypoints to route.
for i=n, N do
-- Copy waypoint.
local wp=UTILS.DeepCopy(self.waypoints[i]) --Ops.OpsGroup#OPSGROUP.Waypoint
if i==n then
---
-- Next Waypoint
---
if Speed then
wp.speed=UTILS.KnotsToMps(Speed)
else
-- Take default waypoint speed.
end
if self.formationPerma then
--if self.formationPerma==ENUMS.Formation.Vehicle.OnRoad then
wp.action=self.formationPerma
--end
elseif Formation then
wp.action=Formation
end
-- Current set formation.
self.option.Formation=wp.action
-- Current set speed in m/s.
self.speedWp=wp.speed
else
---
-- Later Waypoint(s)
---
if self.formationPerma then
wp.action=self.formationPerma
else
-- Take default waypoint speed.
end
end
if wp.roaddist>100 and wp.action==ENUMS.Formation.Vehicle.OnRoad then
-- Waypoint is actually off road!
wp.action=ENUMS.Formation.Vehicle.OffRoad
-- Add "On Road" waypoint in between.
local wproad=wp.roadcoord:WaypointGround(wp.speed, ENUMS.Formation.Vehicle.OnRoad)
table.insert(waypoints, wproad)
end
-- Debug info.
self:T(string.format("WP %d %s: Speed=%d m/s, alt=%d m, Action=%s", i, wp.type, wp.speed, wp.alt, wp.action))
-- Add waypoint.
table.insert(waypoints, wp)
end
-- Current waypoint.
local current=self:GetCoordinate():WaypointGround(UTILS.MpsToKmph(self.speedWp), self.option.Formation)
table.insert(waypoints, 1, current)
table.insert(waypoints, 1, current) -- Seems to be better to add this twice. Otherwise, the passing waypoint functions is triggered to early!
if #waypoints>2 then
self:T(self.lid..string.format("Updateing route: WP %d-->%d-->%d (#%d), Speed=%.1f knots, Formation=%s",
self.currentwp, n, #self.waypoints, #waypoints-2, UTILS.MpsToKnots(self.speedWp), tostring(self.option.Formation)))
-- Route group to all defined waypoints remaining.
self:Route(waypoints)
else
---
-- No waypoints left
---
self:E(self.lid..string.format("WARNING: No waypoints left ==> Full Stop!"))
self:FullStop()
end
end
--- On after "Detour" event.
-- @param #ARMYGROUP self
-- @param #string From From state.
-- @param #string Event Event.
-- @param #string To To state.
-- @param Core.Point#COORDINATE Coordinate Coordinate where to go.
-- @param #number Speed Speed in knots. Default cruise speed.
-- @param #number Formation Formation of the group.
-- @param #number ResumeRoute If true, resume route after detour point was reached. If false, the group will stop at the detour point and wait for futher commands.
function ARMYGROUP:onafterDetour(From, Event, To, Coordinate, Speed, Formation, ResumeRoute)
-- Speed in knots.
Speed=Speed or self:GetSpeedCruise()
-- ID of current waypoint.
local uid=self:GetWaypointCurrent().uid
-- Add waypoint after current.
local wp=self:AddWaypoint(Coordinate, Speed, uid, Formation, true)
-- Set if we want to resume route after reaching the detour waypoint.
if ResumeRoute then
wp.detour=1
else
wp.detour=0
end
end
--- On after "DetourReached" event.
-- @param #ARMYGROUP self
-- @param #string From From state.
-- @param #string Event Event.
-- @param #string To To state.
function ARMYGROUP:onafterDetourReached(From, Event, To)
self:I(self.lid.."Group reached detour coordinate.")
end
--- On after "FullStop" event.
-- @param #ARMYGROUP self
-- @param #string From From state.
-- @param #string Event Event.
-- @param #string To To state.
function ARMYGROUP:onafterFullStop(From, Event, To)
-- Get current position.
local pos=self:GetCoordinate()
-- Create a new waypoint.
local wp=pos:WaypointGround(0)
-- Create new route consisting of only this position ==> Stop!
self:Route({wp})
end
--- On after "Cruise" event.
-- @param #ARMYGROUP self
-- @param #string From From state.
-- @param #string Event Event.
-- @param #string To To state.
-- @param #number Speed Speed in knots.
-- @param #number Formation Formation.
function ARMYGROUP:onafterCruise(From, Event, To, Speed, Formation)
self:__UpdateRoute(-1, nil, Speed, Formation)
end
--- On after Start event. Starts the ARMYGROUP FSM and event handlers.
-- @param #ARMYGROUP self
-- @param #string From From state.
-- @param #string Event Event.
-- @param #string To To state.
function ARMYGROUP:onafterStop(From, Event, To)
-- Handle events:
self:UnHandleEvent(EVENTS.Birth)
self:UnHandleEvent(EVENTS.Dead)
self:UnHandleEvent(EVENTS.RemoveUnit)
-- Call OPSGROUP function.
self:GetParent(self).onafterStop(self, From, Event, To)
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Events DCS
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Event function handling the birth of a unit.
-- @param #ARMYGROUP self
-- @param Core.Event#EVENTDATA EventData Event data.
function ARMYGROUP:OnEventBirth(EventData)
-- Check that this is the right group.
if EventData and EventData.IniGroup and EventData.IniUnit and EventData.IniGroupName and EventData.IniGroupName==self.groupname then
local unit=EventData.IniUnit
local group=EventData.IniGroup
local unitname=EventData.IniUnitName
if self.respawning then
local function reset()
self.respawning=nil
end
-- Reset switch in 1 sec. This should allow all birth events of n>1 groups to have passed.
-- TODO: Can I do this more rigorously?
self:ScheduleOnce(1, reset)
else
-- Get element.
local element=self:GetElementByName(unitname)
-- Set element to spawned state.
self:T3(self.lid..string.format("EVENT: Element %s born ==> spawned", element.name))
self:ElementSpawned(element)
end
end
end
--- Event function handling the crash of a unit.
-- @param #ARMYGROUP self
-- @param Core.Event#EVENTDATA EventData Event data.
function ARMYGROUP:OnEventDead(EventData)
-- Check that this is the right group.
if EventData and EventData.IniGroup and EventData.IniUnit and EventData.IniGroupName and EventData.IniGroupName==self.groupname then
self:T(self.lid..string.format("EVENT: Unit %s dead!", EventData.IniUnitName))
local unit=EventData.IniUnit
local group=EventData.IniGroup
local unitname=EventData.IniUnitName
-- Get element.
local element=self:GetElementByName(unitname)
if element then
self:T(self.lid..string.format("EVENT: Element %s dead ==> destroyed", element.name))
self:ElementDestroyed(element)
end
end
end
--- Event function handling the crash of a unit.
-- @param #ARMYGROUP self
-- @param Core.Event#EVENTDATA EventData Event data.
function ARMYGROUP:OnEventRemoveUnit(EventData)
-- Check that this is the right group.
if EventData and EventData.IniGroup and EventData.IniUnit and EventData.IniGroupName and EventData.IniGroupName==self.groupname then
local unit=EventData.IniUnit
local group=EventData.IniGroup
local unitname=EventData.IniUnitName
-- Get element.
local element=self:GetElementByName(unitname)
if element then
self:T(self.lid..string.format("EVENT: Element %s removed ==> dead", element.name))
self:ElementDead(element)
end
end
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Routing
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Add an a waypoint to the route.
-- @param #ARMYGROUP self
-- @param Core.Point#COORDINATE Coordinate The coordinate of the waypoint. Use COORDINATE:SetAltitude(altitude) to define the altitude.
-- @param #number Speed Speed in knots. Default is default cruise speed or 70% of max speed.
-- @param #number AfterWaypointWithID Insert waypoint after waypoint given ID. Default is to insert as last waypoint.
-- @param #number Formation Formation the group will use.
-- @param #boolean Updateroute If true or nil, call UpdateRoute. If false, no call.
-- @return Ops.OpsGroup#OPSGROUP.Waypoint Waypoint table.
function ARMYGROUP:AddWaypoint(Coordinate, Speed, AfterWaypointWithID, Formation, Updateroute)
-- Set waypoint index.
local wpnumber=self:GetWaypointIndexAfterID(AfterWaypointWithID)
-- Check if final waypoint is still passed.
if wpnumber>self.currentwp then
self.passedfinalwp=false
end
-- Speed in knots.
Speed=Speed or self:GetSpeedCruise()
-- Create a Naval waypoint.
local wp=Coordinate:WaypointGround(UTILS.KnotsToKmph(Speed), Formation)
-- Create waypoint data table.
local waypoint=self:_CreateWaypoint(wp)
-- Add waypoint to table.
self:_AddWaypoint(waypoint, wpnumber)
-- Get closest point to road.
waypoint.roadcoord=Coordinate:GetClosestPointToRoad(false)
if waypoint.roadcoord then
waypoint.roaddist=Coordinate:Get2DDistance(waypoint.roadcoord)
else
waypoint.roaddist=1000*1000 --1000 km.
end
-- Debug info.
self:T(self.lid..string.format("Adding waypoint UID=%d (index=%d), Speed=%.1f knots, Dist2Road=%d m, Action=%s", waypoint.uid, wpnumber, Speed, waypoint.roaddist, waypoint.action))
-- Update route.
if Updateroute==nil or Updateroute==true then
self:_CheckGroupDone(1)
end
return waypoint
end
--- Initialize group parameters. Also initializes waypoints if self.waypoints is nil.
-- @param #ARMYGROUP self
-- @return #ARMYGROUP self
function ARMYGROUP:_InitGroup()
-- First check if group was already initialized.
if self.groupinitialized then
self:E(self.lid.."WARNING: Group was already initialized!")
return
end
-- Get template of group.
self.template=self.group:GetTemplate()
-- Define category.
self.isAircraft=false
self.isNaval=false
self.isGround=true
-- Ships are always AI.
self.ai=true
-- Is (template) group late activated.
self.isLateActivated=self.template.lateActivation
-- Ground groups cannot be uncontrolled.
self.isUncontrolled=false
-- Max speed in km/h.
self.speedMax=self.group:GetSpeedMax()
-- Cruise speed in km/h
self.speedCruise=self.speedMax*0.7
-- Group ammo.
self.ammo=self:GetAmmoTot()
-- Radio parameters from template.
self.radio.On=false -- Radio is always OFF for ground.
self.radio.Freq=133
self.radio.Modu=radio.modulation.AM
-- Set default radio.
self:SetDefaultRadio(self.radio.Freq, self.radio.Modu, self.radio.On)
-- Set default formation from first waypoint.
self.option.Formation=self:GetWaypoint(1).action
self.optionDefault.Formation=self.option.Formation
-- Units of the group.
local units=self.group:GetUnits()
for _,_unit in pairs(units) do
local unit=_unit --Wrapper.Unit#UNIT
local element={} --#ARMYGROUP.Element
element.name=unit:GetName()
element.typename=unit:GetTypeName()
element.status=OPSGROUP.ElementStatus.INUTERO
element.unit=unit
table.insert(self.elements, element)
self:GetAmmoUnit(unit, false)
if unit:IsAlive() then
self:ElementSpawned(element)
end
end
-- Get first unit. This is used to extract other parameters.
local unit=self.group:GetUnit(1)
if unit then
self.descriptors=unit:GetDesc()
self.actype=unit:GetTypeName()
-- Debug info.
if self.verbose>=1 then
local text=string.format("Initialized Army Group %s:\n", self.groupname)
text=text..string.format("Unit type = %s\n", self.actype)
text=text..string.format("Speed max = %.1f Knots\n", UTILS.KmphToKnots(self.speedMax))
text=text..string.format("Speed cruise = %.1f Knots\n", UTILS.KmphToKnots(self.speedCruise))
text=text..string.format("Elements = %d\n", #self.elements)
text=text..string.format("Waypoints = %d\n", #self.waypoints)
text=text..string.format("Radio = %.1f MHz %s %s\n", self.radio.Freq, UTILS.GetModulationName(self.radio.Modu), tostring(self.radio.On))
text=text..string.format("Ammo = %d (G=%d/R=%d/M=%d)\n", self.ammo.Total, self.ammo.Guns, self.ammo.Rockets, self.ammo.Missiles)
text=text..string.format("FSM state = %s\n", self:GetState())
text=text..string.format("Is alive = %s\n", tostring(self:IsAlive()))
text=text..string.format("LateActivate = %s\n", tostring(self:IsLateActivated()))
self:I(self.lid..text)
end
-- Init done.
self.groupinitialized=true
end
return self
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Option Functions
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Switch to a specific formation.
-- @param #ARMYGROUP self
-- @param #number Formation New formation the group will fly in. Default is the setting of `SetDefaultFormation()`.
-- @param #boolean Permanently If true, formation always used from now on.
-- @return #ARMYGROUP self
function ARMYGROUP:SwitchFormation(Formation, Permanently)
if self:IsAlive() then
Formation=Formation or self.optionDefault.Formation
if Permanently then
self.formationPerma=Formation
else
self.formationPerma=nil
end
-- Set current formation.
self.option.Formation=Formation
-- Update route with the new formation.
self:__UpdateRoute(-1, nil, nil, Formation)
-- Debug info.
self:T(self.lid..string.format("Switching formation to %s (permanently=%s)", self.option.Formation, tostring(Permanently)))
end
return self
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Misc Functions
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -15,15 +15,22 @@
-- @type INTEL -- @type INTEL
-- @field #string ClassName Name of the class. -- @field #string ClassName Name of the class.
-- @field #boolean Debug Debug mode. Messages to all about status. -- @field #boolean Debug Debug mode. Messages to all about status.
-- @field #number verbose Verbosity level.
-- @field #string lid Class id string for output to DCS log file. -- @field #string lid Class id string for output to DCS log file.
-- @field #number coalition Coalition side number, e.g. `coalition.side.RED`. -- @field #number coalition Coalition side number, e.g. `coalition.side.RED`.
-- @field #string alias Name of the agency. -- @field #string alias Name of the agency.
-- @field #table filterCategory Category filters. -- @field Core.Set#SET_GROUP detectionset Set of detection groups, aka agents.
-- @field #table filterCategory Filter for unit categories.
-- @field #table filterCategoryGroup Filter for group categories.
-- @field Core.Set#SET_ZONE acceptzoneset Set of accept zones. If defined, only contacts in these zones are considered. -- @field Core.Set#SET_ZONE acceptzoneset Set of accept zones. If defined, only contacts in these zones are considered.
-- @field Core.Set#SET_ZONE rejectzoneset Set of reject zones. Contacts in these zones are not considered, even if they are in accept zones. -- @field Core.Set#SET_ZONE rejectzoneset Set of reject zones. Contacts in these zones are not considered, even if they are in accept zones.
-- @field #table Contacts Table of detected items. -- @field #table Contacts Table of detected items.
-- @field #table ContactsLost Table of lost detected items. -- @field #table ContactsLost Table of lost detected items.
-- @field #table ContactsUnknown Table of new detected items. -- @field #table ContactsUnknown Table of new detected items.
-- @field #table Clusters Clusters of detected groups.
-- @field #boolean clusteranalysis If true, create clusters of detected targets.
-- @field #boolean clustermarkers If true, create cluster markers on F10 map.
-- @field #number clustercounter Running number of clusters.
-- @field #number dTforget Time interval in seconds before a known contact which is not detected any more is forgotten. -- @field #number dTforget Time interval in seconds before a known contact which is not detected any more is forgotten.
-- @extends Core.Fsm#FSM -- @extends Core.Fsm#FSM
@ -41,6 +48,7 @@
INTEL = { INTEL = {
ClassName = "INTEL", ClassName = "INTEL",
Debug = nil, Debug = nil,
verbose = 2,
lid = nil, lid = nil,
alias = nil, alias = nil,
filterCategory = {}, filterCategory = {},
@ -48,6 +56,8 @@ INTEL = {
Contacts = {}, Contacts = {},
ContactsLost = {}, ContactsLost = {},
ContactsUnknown = {}, ContactsUnknown = {},
Clusters = {},
clustercounter = 1,
} }
--- Detected item info. --- Detected item info.
@ -62,8 +72,22 @@ INTEL = {
-- @field #number Tdetected Time stamp in abs. mission time seconds when this item was last detected. -- @field #number Tdetected Time stamp in abs. mission time seconds when this item was last detected.
-- @field Core.Point#COORDINATE position Last known position of the item. -- @field Core.Point#COORDINATE position Last known position of the item.
-- @field DCS#Vec3 velocity 3D velocity vector. Components x,y and z in m/s. -- @field DCS#Vec3 velocity 3D velocity vector. Components x,y and z in m/s.
-- @field #number speed Last known speed. -- @field #number speed Last known speed in m/s.
-- @field #number markerID F10 map marker ID. -- @field #boolean isship
-- @field #boolean ishelo
-- @field #boolean isgrund
--- Cluster info.
-- @type INTEL.Cluster
-- @field #number index Cluster index.
-- @field #number size Number of groups in the cluster.
-- @field #table Contacts Table of contacts in the cluster.
-- @field #number threatlevelMax Max threat level of cluster.
-- @field #number threatlevelSum Sum of threat levels.
-- @field #number threatlevelAve Average of threat levels.
-- @field Core.Point#COORDINATE coordinate Coordinate of the cluster.
-- @field Wrapper.Marker#MARKER marker F10 marker.
--- INTEL class version. --- INTEL class version.
-- @field #string version -- @field #string version
@ -170,7 +194,6 @@ function INTEL:New(DetectionSet, Coalition)
BASE:TraceClass(self.ClassName) BASE:TraceClass(self.ClassName)
BASE:TraceLevel(1) BASE:TraceLevel(1)
end end
self.Debug=true
return self return self
end end
@ -223,6 +246,7 @@ function INTEL:SetFilterCategory(Categories)
if type(Categories)~="table" then if type(Categories)~="table" then
Categories={Categories} Categories={Categories}
end end
self.filterCategory=Categories self.filterCategory=Categories
local text="Filter categories: " local text="Filter categories: "
@ -243,7 +267,7 @@ end
-- * Group.Category.TRAIN -- * Group.Category.TRAIN
-- --
-- @param #INTEL self -- @param #INTEL self
-- @param #table Categories Filter categories, e.g. {Group.Category.AIRPLANE, Group.Category.HELICOPTER}. -- @param #table GroupCategories Filter categories, e.g. `{Group.Category.AIRPLANE, Group.Category.HELICOPTER}`.
-- @return #INTEL self -- @return #INTEL self
function INTEL:FilterCategoryGroup(GroupCategories) function INTEL:FilterCategoryGroup(GroupCategories)
if type(GroupCategories)~="table" then if type(GroupCategories)~="table" then
@ -261,6 +285,17 @@ function INTEL:FilterCategoryGroup(GroupCategories)
return self return self
end end
--- Enable or disable cluster analysis of detected targets.
-- Targets will be grouped in coupled clusters.
-- @param #INTEL self
-- @param #boolean Switch If true, enable cluster analysis.
-- @param #boolean Markers If true, place markers on F10 map.
-- @return #INTEL self
function INTEL:SetClusterAnalysis(Switch, Markers)
self.clusteranalysis=Switch
self.clustermarkers=Markers
return self
end
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Start & Status -- Start & Status
@ -268,7 +303,6 @@ end
--- On after Start event. Starts the FLIGHTGROUP FSM and event handlers. --- On after Start event. Starts the FLIGHTGROUP FSM and event handlers.
-- @param #INTEL self -- @param #INTEL self
-- @param Wrapper.Group#GROUP Group Flight group.
-- @param #string From From state. -- @param #string From From state.
-- @param #string Event Event. -- @param #string Event Event.
-- @param #string To To state. -- @param #string To To state.
@ -284,7 +318,6 @@ end
--- On after "Status" event. --- On after "Status" event.
-- @param #INTEL self -- @param #INTEL self
-- @param Wrapper.Group#GROUP Group Flight group.
-- @param #string From From state. -- @param #string From From state.
-- @param #string Event Event. -- @param #string Event Event.
-- @param #string To To state. -- @param #string To To state.
@ -304,12 +337,14 @@ function INTEL:onafterStatus(From, Event, To)
local Ncontacts=#self.Contacts local Ncontacts=#self.Contacts
-- Short info. -- Short info.
if self.verbose>=1 then
local text=string.format("Status %s [Agents=%s]: Contacts=%d, New=%d, Lost=%d", fsmstate, self.detectionset:CountAlive(), Ncontacts, #self.ContactsUnknown, #self.ContactsLost) local text=string.format("Status %s [Agents=%s]: Contacts=%d, New=%d, Lost=%d", fsmstate, self.detectionset:CountAlive(), Ncontacts, #self.ContactsUnknown, #self.ContactsLost)
self:I(self.lid..text) self:I(self.lid..text)
end
-- Detailed info. -- Detailed info.
if Ncontacts>0 then if self.verbose>=2 and Ncontacts>0 then
text="Detected Contacts:" local text="Detected Contacts:"
for _,_contact in pairs(self.Contacts) do for _,_contact in pairs(self.Contacts) do
local contact=_contact --#INTEL.Contact local contact=_contact --#INTEL.Contact
local dT=timer.getAbsTime()-contact.Tdetected local dT=timer.getAbsTime()-contact.Tdetected
@ -322,7 +357,7 @@ function INTEL:onafterStatus(From, Event, To)
self:I(self.lid..text) self:I(self.lid..text)
end end
self:__Status(-30) self:__Status(-60)
end end
@ -331,28 +366,29 @@ end
function INTEL:UpdateIntel() function INTEL:UpdateIntel()
-- Set of all detected units. -- Set of all detected units.
local DetectedSet=SET_UNIT:New() local DetectedUnits={}
-- Loop over all units providing intel. -- Loop over all units providing intel.
for _,_group in pairs(self.detectionset:GetSet()) do for _,_group in pairs(self.detectionset.Set or {}) do
local group=_group --Wrapper.Group#GROUP local group=_group --Wrapper.Group#GROUP
if group and group:IsAlive() then if group and group:IsAlive() then
for _,_recce in pairs(group:GetUnits()) do for _,_recce in pairs(group:GetUnits()) do
local recce=_recce --Wrapper.Unit#UNIT local recce=_recce --Wrapper.Unit#UNIT
-- Get set of detected units. -- Get detected units.
local detectedunitset=recce:GetDetectedUnitSet() self:GetDetectedUnits(recce, DetectedUnits)
-- Add detected units to all set.
DetectedSet=DetectedSet:GetSetUnion(detectedunitset)
end end
end end
end end
-- TODO: Filter units from reject zones. -- TODO: Filter units from reject zones.
-- TODO: Filter detection methods? -- TODO: Filter detection methods?
local remove={} local remove={}
for _,_unit in pairs(DetectedSet.Set) do for unitname,_unit in pairs(DetectedUnits) do
local unit=_unit --Wrapper.Unit#UNIT local unit=_unit --Wrapper.Unit#UNIT
-- Check if unit is in any of the accept zones. -- Check if unit is in any of the accept zones.
@ -368,7 +404,7 @@ function INTEL:UpdateIntel()
-- Unit is not in accept zone ==> remove! -- Unit is not in accept zone ==> remove!
if not inzone then if not inzone then
table.insert(remove, unit:GetName()) table.insert(remove, unitname)
end end
end end
@ -383,8 +419,8 @@ function INTEL:UpdateIntel()
end end
end end
if not keepit then if not keepit then
self:I(self.lid..string.format("Removing unit %s category=%d", unit:GetName(), unit:GetCategory())) self:I(self.lid..string.format("Removing unit %s category=%d", unitname, unit:GetCategory()))
table.insert(remove, unit:GetName()) table.insert(remove, unitname)
end end
end end
@ -392,42 +428,44 @@ function INTEL:UpdateIntel()
-- Remove filtered units. -- Remove filtered units.
for _,unitname in pairs(remove) do for _,unitname in pairs(remove) do
DetectedSet:Remove(unitname, true) DetectedUnits[unitname]=nil
end
-- Create detected groups.
local DetectedGroups={}
for unitname,_unit in pairs(DetectedUnits) do
local unit=_unit --Wrapper.Unit#UNIT
local group=unit:GetGroup()
if group then
DetectedGroups[group:GetName()]=group
end
end end
-- Create detected contacts. -- Create detected contacts.
self:CreateDetectedItems(DetectedSet) self:CreateDetectedItems(DetectedGroups)
-- Paint a picture of the battlefield.
if self.clusteranalysis then
self:PaintPicture()
end
end end
--- Create detected items. --- Create detected items.
-- @param #INTEL self -- @param #INTEL self
-- @param Core.Set#SET_UNIT detectedunitset Set of detected units. -- @param #table DetectedGroups Table of detected Groups
function INTEL:CreateDetectedItems(detectedunitset) function INTEL:CreateDetectedItems(DetectedGroups)
local detectedgroupset=SET_GROUP:New()
-- Convert detected UNIT set to detected GROUP set.
for _,_unit in pairs(detectedunitset:GetSet()) do
local unit=_unit --Wrapper.Unit#UNIT
local group=unit:GetGroup()
if group and group:IsAlive() then
local groupname=group:GetName()
detectedgroupset:Add(groupname, group)
end
end
-- Current time. -- Current time.
local Tnow=timer.getAbsTime() local Tnow=timer.getAbsTime()
for _,_group in pairs(detectedgroupset.Set) do for groupname,_group in pairs(DetectedGroups) do
local group=_group --Wrapper.Group#GROUP local group=_group --Wrapper.Group#GROUP
-- Group name.
local groupname=group:GetName()
-- Get contact if already known. -- Get contact if already known.
local detecteditem=self:GetContactByName(groupname) local detecteditem=self:GetContactByName(groupname)
@ -457,7 +495,7 @@ function INTEL:CreateDetectedItems(detectedunitset)
item.attribute=group:GetAttribute() item.attribute=group:GetAttribute()
item.category=group:GetCategory() item.category=group:GetCategory()
item.categoryname=group:GetCategoryName() item.categoryname=group:GetCategoryName()
item.threatlevel=group:GetUnit(1):GetThreatLevel() item.threatlevel=group:GetThreatLevel()
item.position=group:GetCoordinate() item.position=group:GetCoordinate()
item.velocity=group:GetVelocityVec3() item.velocity=group:GetVelocityVec3()
item.speed=group:GetVelocityMPS() item.speed=group:GetVelocityMPS()
@ -475,10 +513,8 @@ function INTEL:CreateDetectedItems(detectedunitset)
for i=#self.Contacts,1,-1 do for i=#self.Contacts,1,-1 do
local item=self.Contacts[i] --#INTEL.Contact local item=self.Contacts[i] --#INTEL.Contact
local group=detectedgroupset:FindGroup(item.groupname)
-- Check if deltaT>Tforget. We dont want quick oscillations between detected and undetected states. -- Check if deltaT>Tforget. We dont want quick oscillations between detected and undetected states.
if self:CheckContactLost(item) then if self:_CheckContactLost(item) then
-- Trigger LostContact event. This also adds the contact to the self.ContactsLost table. -- Trigger LostContact event. This also adds the contact to the self.ContactsLost table.
self:LostContact(item) self:LostContact(item)
@ -491,6 +527,41 @@ function INTEL:CreateDetectedItems(detectedunitset)
end end
--- Return the detected target groups of the controllable as a @{SET_GROUP}.
-- The optional parametes specify the detection methods that can be applied.
-- If no detection method is given, the detection will use all the available methods by default.
-- @param #INTEL self
-- @param Wrapper.Unit#UNIT Unit The unit detecting.
-- @param #boolean DetectVisual (Optional) If *false*, do not include visually detected targets.
-- @param #boolean DetectOptical (Optional) If *false*, do not include optically detected targets.
-- @param #boolean DetectRadar (Optional) If *false*, do not include targets detected by radar.
-- @param #boolean DetectIRST (Optional) If *false*, do not include targets detected by IRST.
-- @param #boolean DetectRWR (Optional) If *false*, do not include targets detected by RWR.
-- @param #boolean DetectDLINK (Optional) If *false*, do not include targets detected by data link.
function INTEL:GetDetectedUnits(Unit, DetectedUnits, DetectVisual, DetectOptical, DetectRadar, DetectIRST, DetectRWR, DetectDLINK)
-- Get detected DCS units.
local detectedtargets=Unit:GetDetectedTargets(DetectVisual, DetectOptical, DetectRadar, DetectIRST, DetectRWR, DetectDLINK)
for DetectionObjectID, Detection in pairs(detectedtargets or {}) do
local DetectedObject=Detection.object -- DCS#Object
if DetectedObject and DetectedObject:isExist() and DetectedObject.id_<50000000 then
local unit=UNIT:Find(DetectedObject)
if unit and unit:IsAlive() then
local unitname=unit:GetName()
DetectedUnits[unitname]=unit
end
end
end
end
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- FSM Events -- FSM Events
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
@ -521,10 +592,10 @@ end
-- Misc Functions -- Misc Functions
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Create detected items. --- Get a contact by name.
-- @param #INTEL self -- @param #INTEL self
-- @param #string groupname Name of the contact group. -- @param #string groupname Name of the contact group.
-- @return #INTEL.Contact -- @return #INTEL.Contact The contact.
function INTEL:GetContactByName(groupname) function INTEL:GetContactByName(groupname)
for i,_contact in pairs(self.Contacts) do for i,_contact in pairs(self.Contacts) do
@ -539,7 +610,7 @@ end
--- Add a contact to our list. --- Add a contact to our list.
-- @param #INTEL self -- @param #INTEL self
-- @param #INTEL.Contact Contact The contact to be removed. -- @param #INTEL.Contact Contact The contact to be added.
function INTEL:AddContact(Contact) function INTEL:AddContact(Contact)
table.insert(self.Contacts, Contact) table.insert(self.Contacts, Contact)
end end
@ -560,11 +631,11 @@ function INTEL:RemoveContact(Contact)
end end
--- Remove a contact from our list. --- Check if a contact was lost.
-- @param #INTEL self -- @param #INTEL self
-- @param #INTEL.Contact Contact The contact to be removed. -- @param #INTEL.Contact Contact The contact to be removed.
-- @return #boolean If true, contact was not detected for at least *dTforget* seconds. -- @return #boolean If true, contact was not detected for at least *dTforget* seconds.
function INTEL:CheckContactLost(Contact) function INTEL:_CheckContactLost(Contact)
-- Group dead? -- Group dead?
if Contact.group==nil or not Contact.group:IsAlive() then if Contact.group==nil or not Contact.group:IsAlive() then
@ -595,6 +666,378 @@ function INTEL:CheckContactLost(Contact)
end end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Cluster Functions
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Paint picture of the battle field.
-- @param #INTEL self
function INTEL:PaintPicture()
-- First remove all lost contacts from clusters.
for _,_contact in pairs(self.ContactsLost) do
local contact=_contact --#INTEL.Contact
local cluster=self:GetClusterOfContact(contact)
if cluster then
self:RemoveContactFromCluster(contact, cluster)
end
end
for _,_contact in pairs(self.Contacts) do
local contact=_contact --#INTEL.Contact
-- Check if this contact is in any cluster.
local isincluster=self:CheckContactInClusters(contact)
-- Get the current cluster (if any) this contact belongs to.
local currentcluster=self:GetClusterOfContact(contact)
if currentcluster then
---
-- Contact is currently part of a cluster.
---
-- Check if the contact is still connected to the cluster.
local isconnected=self:IsContactConnectedToCluster(contact, currentcluster)
if not isconnected then
local cluster=self:IsContactPartOfAnyClusters(contact)
if cluster then
self:AddContactToCluster(contact, cluster)
else
local newcluster=self:CreateCluster(contact.position)
self:AddContactToCluster(contact, newcluster)
end
end
else
---
-- Contact is not in any cluster yet.
---
local cluster=self:IsContactPartOfAnyClusters(contact)
if cluster then
self:AddContactToCluster(contact, cluster)
else
local newcluster=self:CreateCluster(contact.position)
self:AddContactToCluster(contact, newcluster)
end
end
end
-- Update F10 marker text if cluster has changed.
for _,_cluster in pairs(self.Clusters) do
local cluster=_cluster --#INTEL.Cluster
local coordinate=self:GetClusterCoordinate(cluster)
-- Update F10 marker.
self:UpdateClusterMarker(cluster)
end
end
--- Create a new cluster.
-- @param #INTEL self
-- @param Core.Point#COORDINATE coordinate The coordinate of the cluster.
-- @return #INTEL.Cluster cluster The cluster.
function INTEL:CreateCluster(coordinate)
-- Create new cluster
local cluster={} --#INTEL.Cluster
cluster.index=self.clustercounter
cluster.coordinate=coordinate
cluster.threatlevelSum=0
cluster.threatlevelMax=0
cluster.size=0
cluster.Contacts={}
-- Add cluster.
table.insert(self.Clusters, cluster)
-- Increase counter.
self.clustercounter=self.clustercounter+1
return cluster
end
--- Add a contact to the cluster.
-- @param #INTEL self
-- @param #INTEL.Contact contact The contact.
-- @param #INTEL.Cluster cluster The cluster.
function INTEL:AddContactToCluster(contact, cluster)
if contact and cluster then
-- Add neighbour to cluster contacts.
table.insert(cluster.Contacts, contact)
cluster.threatlevelSum=cluster.threatlevelSum+contact.threatlevel
cluster.size=cluster.size+1
end
end
--- Remove a contact from a cluster.
-- @param #INTEL self
-- @param #INTEL.Contact contact The contact.
-- @param #INTEL.Cluster cluster The cluster.
function INTEL:RemoveContactFromCluster(contact, cluster)
if contact and cluster then
for i,_contact in pairs(cluster.Contacts) do
local Contact=_contact --#INTEL.Contact
if Contact.groupname==contact.groupname then
cluster.threatlevelSum=cluster.threatlevelSum-contact.threatlevel
cluster.size=cluster.size-1
table.remove(cluster.Contacts, i)
return
end
end
end
end
--- Calculate cluster threat level sum.
-- @param #INTEL self
-- @param #INTEL.Cluster cluster The cluster of contacts.
-- @return #number Sum of all threat levels of all groups in the cluster.
function INTEL:CalcClusterThreatlevelSum(cluster)
local threatlevel=0
for _,_contact in pairs(cluster.Contacts) do
local contact=_contact --#INTEL.Contact
threatlevel=threatlevel+contact.threatlevel
end
return threatlevel
end
--- Calculate cluster threat level average.
-- @param #INTEL self
-- @param #INTEL.Cluster cluster The cluster of contacts.
-- @return #number Average of all threat levels of all groups in the cluster.
function INTEL:CalcClusterThreatlevelAverage(cluster)
local threatlevel=self:CalcClusterThreatlevelSum(cluster)
threatlevel=threatlevel/cluster.size
return threatlevel
end
--- Calculate max cluster threat level.
-- @param #INTEL self
-- @param #INTEL.Cluster cluster The cluster of contacts.
-- @return #number Max threat levels of all groups in the cluster.
function INTEL:CalcClusterThreatlevelMax(cluster)
local threatlevel=0
for _,_contact in pairs(cluster.Contacts) do
local contact=_contact --#INTEL.Contact
if contact.threatlevel>threatlevel then
threatlevel=contact.threatlevel
end
end
return threatlevel
end
--- Check if contact is in any known cluster.
-- @param #INTEL self
-- @param #INTEL.Contact contact The contact.
-- @return #boolean If true, contact is in clusters
function INTEL:CheckContactInClusters(contact)
for _,_cluster in pairs(self.Clusters) do
local cluster=_cluster --#INTEL.Cluster
for _,_contact in pairs(cluster.Contacts) do
local Contact=_contact --#INTEL.Contact
if Contact.groupname==contact.groupname then
return true
end
end
end
return false
end
--- Check if contact is close to any other contact this cluster.
-- @param #INTEL self
-- @param #INTEL.Contact contact The contact.
-- @param #INTEL.Cluster cluster The cluster the check.
-- @return #boolean If true, contact is connected to this cluster.
function INTEL:IsContactConnectedToCluster(contact, cluster)
for _,_contact in pairs(cluster.Contacts) do
local Contact=_contact --#INTEL.Contact
if Contact.groupname~=contact.groupname then
local dist=Contact.position:Get2DDistance(contact.position)
if dist<10*1000 then
return true
end
end
end
return false
end
--- Check if contact is close to any contact of known clusters.
-- @param #INTEL self
-- @param #INTEL.Contact contact The contact.
-- @return #INTEL.Cluster The cluster this contact is part of or nil otherwise.
function INTEL:IsContactPartOfAnyClusters(contact)
for _,_cluster in pairs(self.Clusters) do
local cluster=_cluster --#INTEL.Cluster
if self:IsContactConnectedToCluster(contact, cluster) then
return cluster
end
end
return nil
end
--- Get the cluster this contact belongs to (if any).
-- @param #INTEL self
-- @param #INTEL.Contact contact The contact.
-- @return #INTEL.Cluster The cluster this contact belongs to or nil.
function INTEL:GetClusterOfContact(contact)
for _,_cluster in pairs(self.Clusters) do
local cluster=_cluster --#INTEL.Cluster
for _,_contact in pairs(cluster.Contacts) do
local Contact=_contact --#INTEL.Contact
if Contact.groupname==contact.groupname then
return cluster
end
end
end
return nil
end
--- Get the coordinate of a cluster.
-- @param #INTEL self
-- @param #INTEL.Cluster cluster The cluster.
-- @return Core.Point#COORDINATE The coordinate of this cluster.
function INTEL:GetClusterCoordinate(cluster)
-- Init.
local x=0 ; local y=0 ; local z=0 ; local n=0
for _,_contact in pairs(cluster.Contacts) do
local contact=_contact --#INTEL.Contact
x=x+contact.position.x
y=y+contact.position.y
z=z+contact.position.z
n=n+1
end
-- Average.
x=x/n ; y=y/n ; z=z/n
-- Create coordinate.
local coordinate=COORDINATE:New(x, y, z)
return coordinate
end
--- Get the coordinate of a cluster.
-- @param #INTEL self
-- @param #INTEL.Cluster cluster The cluster.
-- @param Core.Point#COORDINATE coordinate (Optional) Coordinate of the new cluster. Default is to calculate the current coordinate.
function INTEL:CheckClusterCoordinateChanged(cluster, coordinate)
coordinate=coordinate or self:GetClusterCoordinate(cluster)
local dist=cluster.coordinate:Get2DDistance(coordinate)
if dist>1000 then
return true
else
return false
end
end
--- Update cluster F10 marker.
-- @param #INTEL self
-- @param #INTEL.Cluster cluster The cluster.
-- @return #INTEL self
function INTEL:UpdateClusterMarker(cluster)
-- Create a marker.
local text=string.format("Cluster #%d. Size %d, TLsum=%d", cluster.index, cluster.size, cluster.threatlevelSum)
if not cluster.marker then
cluster.marker=MARKER:New(cluster.coordinate, text):ToAll()
else
local refresh=false
if cluster.marker.text~=text then
cluster.marker.text=text
refresh=true
end
if cluster.marker.coordinate~=cluster.coordinate then
cluster.marker.coordinate=cluster.coordinate
refresh=true
end
if refresh then
cluster.marker:Refresh()
end
end
return self
end
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -17,14 +17,19 @@
--- SQUADRON class. --- SQUADRON class.
-- @type SQUADRON -- @type SQUADRON
-- @field #string ClassName Name of the class. -- @field #string ClassName Name of the class.
-- @field #boolean Debug Debug mode. Messages to all about status. -- @field #number verbose Verbosity level.
-- @field #string lid Class id string for output to DCS log file. -- @field #string lid Class id string for output to DCS log file.
-- @field #string name Name of the squadron. -- @field #string name Name of the squadron.
-- @field #string templatename Name of the template group. -- @field #string templatename Name of the template group.
-- @field #string aircrafttype Type of the airframe the squadron is using. -- @field #string aircrafttype Type of the airframe the squadron is using.
-- @field Wrapper.Group#GROUP templategroup Template group. -- @field Wrapper.Group#GROUP templategroup Template group.
-- @field #number ngrouping User defined number of units in the asset group.
-- @field #table assets Squadron assets. -- @field #table assets Squadron assets.
-- @field #table missiontypes Capabilities (mission types and performances) of the squadron. -- @field #table missiontypes Capabilities (mission types and performances) of the squadron.
-- @field #number fuellow Low fuel threshold.
-- @field #boolean fuellowRefuel If `true`, flight tries to refuel at the nearest tanker.
-- @field #number maintenancetime Time in seconds needed for maintenance of a returned flight.
-- @field #number repairtime Time in seconds for each
-- @field #string livery Livery of the squadron. -- @field #string livery Livery of the squadron.
-- @field #number skill Skill of squadron members. -- @field #number skill Skill of squadron members.
-- @field #number modex Modex. -- @field #number modex Modex.
@ -33,13 +38,11 @@
-- @field #number callsigncounter Counter to increase callsign names for new assets. -- @field #number callsigncounter Counter to increase callsign names for new assets.
-- @field Ops.AirWing#AIRWING airwing The AIRWING object the squadron belongs to. -- @field Ops.AirWing#AIRWING airwing The AIRWING object the squadron belongs to.
-- @field #number Ngroups Number of asset flight groups this squadron has. -- @field #number Ngroups Number of asset flight groups this squadron has.
-- @field #number engageRange Engagement range in meters. -- @field #number engageRange Mission range in meters.
-- @field #string attribute Generalized attribute of the squadron template group. -- @field #string attribute Generalized attribute of the squadron template group.
-- @field #number tankerSystem For tanker squads, the refuel system used (boom=0 or probpe=1). Default nil. -- @field #number tankerSystem For tanker squads, the refuel system used (boom=0 or probpe=1). Default nil.
-- @field #number refuelSystem For refuelable squads, the refuel system used (boom=0 or probpe=1). Default nil. -- @field #number refuelSystem For refuelable squads, the refuel system used (boom=0 or probe=1). Default nil.
-- @field #number TACANmin TACAN min channel. -- @field #table tacanChannel List of TACAN channels available to the squadron.
-- @field #number TACANmax TACAN max channel.
-- @field #table TACANused Table of used TACAN channels.
-- @field #number radioFreq Radio frequency in MHz the squad uses. -- @field #number radioFreq Radio frequency in MHz the squad uses.
-- @field #number radioModu Radio modulation the squad uses. -- @field #number radioModu Radio modulation the squad uses.
-- @extends Core.Fsm#FSM -- @extends Core.Fsm#FSM
@ -48,7 +51,7 @@
-- --
-- === -- ===
-- --
-- ![Banner Image](..\Presentations\Squadron\SQUADRON_Main.jpg) -- ![Banner Image](..\Presentations\OPS\Squadron\_Main.png)
-- --
-- # The SQUADRON Concept -- # The SQUADRON Concept
-- --
@ -59,13 +62,15 @@
-- @field #SQUADRON -- @field #SQUADRON
SQUADRON = { SQUADRON = {
ClassName = "SQUADRON", ClassName = "SQUADRON",
Debug = nil, verbose = 0,
lid = nil, lid = nil,
name = nil, name = nil,
templatename = nil, templatename = nil,
aircrafttype = nil, aircrafttype = nil,
assets = {}, assets = {},
missiontypes = {}, missiontypes = {},
repairtime = 0,
maintenancetime= 0,
livery = nil, livery = nil,
skill = nil, skill = nil,
modex = nil, modex = nil,
@ -77,14 +82,12 @@ SQUADRON = {
engageRange = nil, engageRange = nil,
tankerSystem = nil, tankerSystem = nil,
refuelSystem = nil, refuelSystem = nil,
TACANmin = nil, tacanChannel = {},
TACANmax = nil,
TACANused = {},
} }
--- SQUADRON class version. --- SQUADRON class version.
-- @field #string version -- @field #string version
SQUADRON.version="0.1.0" SQUADRON.version="0.5.0"
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO list -- TODO list
@ -129,15 +132,20 @@ function SQUADRON:New(TemplateGroupName, Ngroups, SquadronName)
-- Defaults. -- Defaults.
self.Ngroups=Ngroups or 3 self.Ngroups=Ngroups or 3
self:SetEngagementRange() self:SetMissionRange()
self:SetSkill(AI.Skill.GOOD)
--self:SetVerbosity(0)
-- Everyone can ORBIT. -- Everyone can ORBIT.
self:AddMissonCapability(AUFTRAG.Type.ORBIT) self:AddMissionCapability(AUFTRAG.Type.ORBIT)
-- Generalized attribute.
self.attribute=self.templategroup:GetAttribute() self.attribute=self.templategroup:GetAttribute()
-- Aircraft type.
self.aircrafttype=self.templategroup:GetTypeName() self.aircrafttype=self.templategroup:GetTypeName()
-- Refueling system.
self.refuelSystem=select(2, self.templategroup:GetUnit(1):IsRefuelable()) self.refuelSystem=select(2, self.templategroup:GetUnit(1):IsRefuelable())
self.tankerSystem=select(2, self.templategroup:GetUnit(1):IsTanker()) self.tankerSystem=select(2, self.templategroup:GetUnit(1):IsTanker())
@ -149,8 +157,10 @@ function SQUADRON:New(TemplateGroupName, Ngroups, SquadronName)
-- From State --> Event --> To State -- From State --> Event --> To State
self:AddTransition("Stopped", "Start", "OnDuty") -- Start FSM. self:AddTransition("Stopped", "Start", "OnDuty") -- Start FSM.
self:AddTransition("*", "Status", "*") -- Status update. self:AddTransition("*", "Status", "*") -- Status update.
self:AddTransition("OnDuty", "Pause", "Paused") -- Pause squadron. self:AddTransition("OnDuty", "Pause", "Paused") -- Pause squadron.
self:AddTransition("Paused", "Unpause", "OnDuty") -- Unpause squadron. self:AddTransition("Paused", "Unpause", "OnDuty") -- Unpause squadron.
self:AddTransition("*", "Stop", "Stopped") -- Stop squadron. self:AddTransition("*", "Stop", "Stopped") -- Stop squadron.
@ -187,13 +197,10 @@ function SQUADRON:New(TemplateGroupName, Ngroups, SquadronName)
-- Debug trace. -- Debug trace.
if false then if false then
self.Debug=true
BASE:TraceOnOff(true) BASE:TraceOnOff(true)
BASE:TraceClass(self.ClassName) BASE:TraceClass(self.ClassName)
BASE:TraceLevel(1) BASE:TraceLevel(1)
end end
self.Debug=true
return self return self
end end
@ -232,6 +239,26 @@ function SQUADRON:SetSkill(Skill)
return self return self
end end
--- Set verbosity level.
-- @param #SQUADRON self
-- @param #number VerbosityLevel Level of output (higher=more). Default 0.
-- @return #SQUADRON self
function SQUADRON:SetVerbosity(VerbosityLevel)
self.verbose=VerbosityLevel or 0
return self
end
--- Set turnover and repair time. If an asset returns from a mission to the airwing, it will need some time until the asset is available for further missions.
-- @param #SQUADRON self
-- @param #number MaintenanceTime Time in minutes it takes until a flight is combat ready again. Default is 0 min.
-- @param #number RepairTime Time in minutes it takes to repair a flight for each life point taken. Default is 0 min.
-- @return #SQUADRON self
function SQUADRON:SetTurnoverTime(MaintenanceTime, RepairTime)
self.maintenancetime=MaintenanceTime and MaintenanceTime*60 or 0
self.repairtime=RepairTime and RepairTime*60 or 0
return self
end
--- Set radio frequency and modulation the squad uses. --- Set radio frequency and modulation the squad uses.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @param #number Frequency Radio frequency in MHz. Default 251 MHz. -- @param #number Frequency Radio frequency in MHz. Default 251 MHz.
@ -244,12 +271,23 @@ function SQUADRON:SetRadio(Frequency, Modulation)
return self return self
end end
--- Set number of units in groups.
-- @param #SQUADRON self
-- @param #number nunits Number of units. Must be >=1 and <=4. Default 2.
-- @return #SQUADRON self
function SQUADRON:SetGrouping(nunits)
self.ngrouping=nunits or 2
if self.ngrouping<1 then self.ngrouping=1 end
if self.ngrouping>4 then self.ngrouping=4 end
return self
end
--- Set mission types this squadron is able to perform. --- Set mission types this squadron is able to perform.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @param #table MissionTypes Table of mission types. Can also be passed as a #string if only one type. -- @param #table MissionTypes Table of mission types. Can also be passed as a #string if only one type.
-- @param #number Performance Performance describing how good this mission can be performed. Higher is better. Default 50. Max 100. -- @param #number Performance Performance describing how good this mission can be performed. Higher is better. Default 50. Max 100.
-- @return #SQUADRON self -- @return #SQUADRON self
function SQUADRON:AddMissonCapability(MissionTypes, Performance) function SQUADRON:AddMissionCapability(MissionTypes, Performance)
-- Ensure Missiontypes is a table. -- Ensure Missiontypes is a table.
if MissionTypes and type(MissionTypes)~="table" then if MissionTypes and type(MissionTypes)~="table" then
@ -276,7 +314,7 @@ function SQUADRON:AddMissonCapability(MissionTypes, Performance)
end end
-- Debug info. -- Debug info.
self:I(self.missiontypes) self:T2(self.missiontypes)
return self return self
end end
@ -319,12 +357,12 @@ function SQUADRON:GetMissionPeformance(MissionType)
return -1 return -1
end end
--- Set max engagement range. --- Set max mission range. Only missions in a circle of this radius around the squadron airbase are executed.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @param #number EngageRange Engagement range in NM. Default 80 NM. -- @param #number Range Range in NM. Default 100 NM.
-- @return #SQUADRON self -- @return #SQUADRON self
function SQUADRON:SetEngagementRange(EngageRange) function SQUADRON:SetMissionRange(Range)
self.engageRange=UTILS.NMToMeters(EngageRange or 80) self.engageRange=UTILS.NMToMeters(Range or 100)
return self return self
end end
@ -352,6 +390,28 @@ function SQUADRON:SetModex(Modex, Prefix, Suffix)
return self return self
end end
--- Set low fuel threshold.
-- @param #SQUADRON self
-- @param #number LowFuel Low fuel threshold in percent. Default 25.
-- @return #SQUADRON self
function SQUADRON:SetFuelLowThreshold(LowFuel)
self.fuellow=LowFuel or 25
return self
end
--- Set if low fuel threshold is reached, flight tries to refuel at the neares tanker.
-- @param #SQUADRON self
-- @param #boolean switch If true or nil, flight goes for refuelling. If false, turn this off.
-- @return #SQUADRON self
function SQUADRON:SetFuelLowRefuel(switch)
if switch==false then
self.fuellowRefuel=false
else
self.fuellowRefuel=true
end
return self
end
--- Set airwing. --- Set airwing.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @param Ops.AirWing#AIRWING Airwing The airwing. -- @param Ops.AirWing#AIRWING Airwing The airwing.
@ -361,7 +421,6 @@ function SQUADRON:SetAirwing(Airwing)
return self return self
end end
--- Add airwing asset to squadron. --- Add airwing asset to squadron.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @param Ops.AirWing#AIRWING.SquadronAsset Asset The airwing asset. -- @param Ops.AirWing#AIRWING.SquadronAsset Asset The airwing asset.
@ -389,6 +448,29 @@ function SQUADRON:DelAsset(Asset)
return self return self
end end
--- Remove airwing asset group from squadron.
-- @param #SQUADRON self
-- @param #string GroupName Name of the asset group.
-- @return #SQUADRON self
function SQUADRON:DelGroup(GroupName)
for i,_asset in pairs(self.assets) do
local asset=_asset --Ops.AirWing#AIRWING.SquadronAsset
if GroupName==asset.spawngroupname then
self:T2(self.lid..string.format("Removing asset %s", asset.spawngroupname))
table.remove(self.assets, i)
break
end
end
return self
end
--- Get name of the squadron
-- @param #SQUADRON self
-- @return #string Name of the squadron.
function SQUADRON:GetName()
return self.name
end
--- Get radio frequency and modulation. --- Get radio frequency and modulation.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @return #number Radio frequency in MHz. -- @return #number Radio frequency in MHz.
@ -410,6 +492,7 @@ function SQUADRON:GetCallsign(Asset)
for i=1,Asset.nunits do for i=1,Asset.nunits do
local callsign={} local callsign={}
callsign[1]=self.callsignName callsign[1]=self.callsignName
callsign[2]=math.floor(self.callsigncounter / 10) callsign[2]=math.floor(self.callsigncounter / 10)
callsign[3]=self.callsigncounter % 10 callsign[3]=self.callsigncounter % 10
@ -456,23 +539,34 @@ function SQUADRON:GetModex(Asset)
end end
--- Add TACAN channels to the squadron. Note that channels can only range from 1 to 126.
-- @param #SQUADRON self
-- @param #number ChannelMin Channel.
-- @param #number ChannelMax Channel.
-- @return #SQUADRON self
-- @usage mysquad:AddTacanChannel(64,69) -- adds channels 64, 65, 66, 67, 68, 69
function SQUADRON:AddTacanChannel(ChannelMin, ChannelMax)
ChannelMax=ChannelMax or ChannelMin
for i=ChannelMin,ChannelMax do
self.tacanChannel[i]=true
end
end
--- Get an unused TACAN channel. --- Get an unused TACAN channel.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @param Ops.AirWing#AIRWING.SquadronAsset Asset The airwing asset.
-- @return #number TACAN channel or *nil* if no channel is free. -- @return #number TACAN channel or *nil* if no channel is free.
function SQUADRON:GetTACAN() function SQUADRON:FetchTacan()
if self.TACANmin and self.TACANmax then for channel,free in pairs(self.tacanChannel) do
if free then
for channel=self.TACANmin, self.TACANmax do self:T(self.lid..string.format("Checking out Tacan channel %d", channel))
self.tacanChannel[channel]=false
if not self.TACANused[channel] then
self.TACANused[channel]=true
return channel return channel
end end
end
end end
return nil return nil
@ -481,8 +575,9 @@ end
--- "Return" a used TACAN channel. --- "Return" a used TACAN channel.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @param #number channel The channel that is available again. -- @param #number channel The channel that is available again.
function SQUADRON:ReturnTACAN(channel) function SQUADRON:ReturnTacan(channel)
self.TACANused[channel]=false self:T(self.lid..string.format("Returning Tacan channel %d", channel))
self.tacanChannel[channel]=true
end end
--- Check if squadron is "OnDuty". --- Check if squadron is "OnDuty".
@ -520,7 +615,7 @@ function SQUADRON:onafterStart(From, Event, To)
-- Short info. -- Short info.
local text=string.format("Starting SQUADRON", self.name) local text=string.format("Starting SQUADRON", self.name)
self:I(self.lid..text) self:T(self.lid..text)
-- Start the status monitoring. -- Start the status monitoring.
self:__Status(-1) self:__Status(-1)
@ -533,18 +628,34 @@ end
-- @param #string To To state. -- @param #string To To state.
function SQUADRON:onafterStatus(From, Event, To) function SQUADRON:onafterStatus(From, Event, To)
if self.verbose>=1 then
-- FSM state. -- FSM state.
local fsmstate=self:GetState() local fsmstate=self:GetState()
-- Check if group has detected any units. local callsign=self.callsignName and UTILS.GetCallsignName(self.callsignName) or "N/A"
--self:_CheckAssetStatus() local modex=self.modex and self.modex or -1
local skill=self.skill and tostring(self.skill) or "N/A"
local NassetsTot=#self.assets
local NassetsInS=self:CountAssetsInStock()
local NassetsQP=0 ; local NassetsP=0 ; local NassetsQ=0
if self.airwing then
NassetsQP, NassetsP, NassetsQ=self.airwing:CountAssetsOnMission(nil, self)
end
-- Short info. -- Short info.
local text=string.format("Status %s: Assets %d", fsmstate, #self.assets) local text=string.format("%s [Type=%s, Call=%s, Modex=%d, Skill=%s]: Assets Total=%d, Stock=%d, Mission=%d [Active=%d, Queue=%d]",
fsmstate, self.aircrafttype, callsign, modex, skill, NassetsTot, NassetsInS, NassetsQP, NassetsP, NassetsQ)
self:I(self.lid..text) self:I(self.lid..text)
-- Check if group has detected any units.
self:_CheckAssetStatus()
end
if not self:IsStopped() then if not self:IsStopped() then
self:__Status(-30) self:__Status(-60)
end end
end end
@ -553,9 +664,85 @@ end
-- @param #SQUADRON self -- @param #SQUADRON self
function SQUADRON:_CheckAssetStatus() function SQUADRON:_CheckAssetStatus()
for _,_asset in pairs(self.assets) do if self.verbose>=2 and #self.assets>0 then
local asset=_asset
local text=""
for j,_asset in pairs(self.assets) do
local asset=_asset --Ops.AirWing#AIRWING.SquadronAsset
-- Text.
text=text..string.format("\n[%d] %s (%s*%d): ", j, asset.spawngroupname, asset.unittype, asset.nunits)
if asset.spawned then
---
-- Spawned
---
-- Mission info.
local mission=self.airwing and self.airwing:GetAssetCurrentMission(asset) or false
if mission then
local distance=asset.flightgroup and UTILS.MetersToNM(mission:GetTargetDistance(asset.flightgroup.group:GetCoordinate())) or 0
text=text..string.format("Mission %s - %s: Status=%s, Dist=%.1f NM", mission.name, mission.type, mission.status, distance)
else
text=text.."Mission None"
end
-- Flight status.
text=text..", Flight: "
if asset.flightgroup and asset.flightgroup:IsAlive() then
local status=asset.flightgroup:GetState()
local fuelmin=asset.flightgroup:GetFuelMin()
local fuellow=asset.flightgroup:IsFuelLow()
local fuelcri=asset.flightgroup:IsFuelCritical()
text=text..string.format("%s Fuel=%d", status, fuelmin)
if fuelcri then
text=text.." (Critical!)"
elseif fuellow then
text=text.." (Low)"
end
local lifept, lifept0=asset.flightgroup:GetLifePoints()
text=text..string.format(", Life=%d/%d", lifept, lifept0)
local ammo=asset.flightgroup:GetAmmoTot()
text=text..string.format(", Ammo=%d [G=%d, R=%d, B=%d, M=%d]", ammo.Total,ammo.Guns, ammo.Rockets, ammo.Bombs, ammo.Missiles)
else
text=text.."N/A"
end
-- Payload info.
local payload=asset.payload and table.concat(self.airwing:GetPayloadMissionTypes(asset.payload), ", ") or "None"
text=text..", Payload={"..payload.."}"
else
---
-- In Stock
---
text=text..string.format("In Stock")
if self:IsRepaired(asset) then
text=text..", Combat Ready"
else
text=text..string.format(", Repaired in %d sec", self:GetRepairTime(asset))
if asset.damage then
text=text..string.format(" (Damage=%.1f)", asset.damage)
end
end
if asset.Treturned then
local T=timer.getAbsTime()-asset.Treturned
text=text..string.format(", Returned for %d sec", T)
end
end
end
self:I(self.lid..text)
end end
end end
@ -575,6 +762,8 @@ function SQUADRON:onafterStop(From, Event, To)
self:DelAsset(asset) self:DelAsset(asset)
end end
self.CallScheduler:Clear()
end end
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
@ -592,13 +781,13 @@ function SQUADRON:CanMission(Mission)
-- On duty?= -- On duty?=
if not self:IsOnDuty() then if not self:IsOnDuty() then
self:I(self.lid..string.format("Squad in not OnDuty but in state %s. Cannot do mission %s with target %s", self:GetState(), Mission.name, Mission:GetTargetName())) self:T(self.lid..string.format("Squad in not OnDuty but in state %s. Cannot do mission %s with target %s", self:GetState(), Mission.name, Mission:GetTargetName()))
return false return false
end end
-- Check mission type. WARNING: This assumes that all assets of the squad can do the same mission types! -- Check mission type. WARNING: This assumes that all assets of the squad can do the same mission types!
if not self:CheckMissionType(Mission.type, self:GetMissionTypes()) then if not self:CheckMissionType(Mission.type, self:GetMissionTypes()) then
self:I(self.lid..string.format("INFO: Squad cannot do mission type %s (%s, %s)", Mission.type, Mission.name, Mission:GetTargetName())) self:T(self.lid..string.format("INFO: Squad cannot do mission type %s (%s, %s)", Mission.type, Mission.name, Mission:GetTargetName()))
return false return false
end end
@ -608,7 +797,7 @@ function SQUADRON:CanMission(Mission)
if Mission.refuelSystem and Mission.refuelSystem==self.tankerSystem then if Mission.refuelSystem and Mission.refuelSystem==self.tankerSystem then
-- Correct refueling system. -- Correct refueling system.
else else
self:I(self.lid..string.format("INFO: Wrong refueling system requested=%s != %s=available", tostring(Mission.refuelSystem), tostring(self.tankerSystem))) self:T(self.lid..string.format("INFO: Wrong refueling system requested=%s != %s=available", tostring(Mission.refuelSystem), tostring(self.tankerSystem)))
return false return false
end end
@ -622,14 +811,14 @@ function SQUADRON:CanMission(Mission)
-- Set range is valid. Mission engage distance can overrule the squad engage range. -- Set range is valid. Mission engage distance can overrule the squad engage range.
if TargetDistance>engagerange then if TargetDistance>engagerange then
self:I(self.lid..string.format("INFO: Squad is not in range. Target dist=%d > %d NM max engage Range", UTILS.MetersToNM(TargetDistance), UTILS.MetersToNM(engagerange))) self:I(self.lid..string.format("INFO: Squad is not in range. Target dist=%d > %d NM max mission Range", UTILS.MetersToNM(TargetDistance), UTILS.MetersToNM(engagerange)))
return false return false
end end
return true return true
end end
--- Get assets for a mission. --- Count assets in airwing (warehous) stock.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @return #number Assets not spawned. -- @return #number Assets not spawned.
function SQUADRON:CountAssetsInStock() function SQUADRON:CountAssetsInStock()
@ -650,11 +839,12 @@ end
--- Get assets for a mission. --- Get assets for a mission.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @param Ops.Auftrag#AUFTRAG Mission The mission. -- @param Ops.Auftrag#AUFTRAG Mission The mission.
-- @param #number Nplayloads Number of payloads available.
-- @return #table Assets that can do the required mission. -- @return #table Assets that can do the required mission.
function SQUADRON:RecruitAssets(Mission) function SQUADRON:RecruitAssets(Mission, Npayloads)
-- Number of payloads available. -- Number of payloads available.
local Npayloads=self.airwing:CountPayloadsInStock(Mission.type, self.aircrafttype) Npayloads=Npayloads or self.airwing:CountPayloadsInStock(Mission.type, self.aircrafttype, Mission.payloads)
local assets={} local assets={}
@ -670,12 +860,12 @@ function SQUADRON:RecruitAssets(Mission)
-- Asset is already on a mission. -- Asset is already on a mission.
--- ---
-- Check if this asset is currently on a PATROL mission (STARTED or EXECUTING). -- Check if this asset is currently on a GCICAP mission (STARTED or EXECUTING).
if self.airwing:IsAssetOnMission(asset, AUFTRAG.Type.PATROL) and Mission.type==AUFTRAG.Type.INTERCEPT then if self.airwing:IsAssetOnMission(asset, AUFTRAG.Type.GCICAP) and Mission.type==AUFTRAG.Type.INTERCEPT then
-- Check if the payload of this asset is compatible with the mission. -- Check if the payload of this asset is compatible with the mission.
-- Note: we do not check the payload as an asset that is on a PATROL mission should be able to do an INTERCEPT as well! -- Note: we do not check the payload as an asset that is on a GCICAP mission should be able to do an INTERCEPT as well!
self:I(self.lid.."Adding asset on PATROL mission for an INTERCEPT mission") self:I(self.lid.."Adding asset on GCICAP mission for an INTERCEPT mission")
table.insert(assets, asset) table.insert(assets, asset)
end end
@ -683,7 +873,7 @@ function SQUADRON:RecruitAssets(Mission)
else else
--- ---
-- Asset as no current mission -- Asset as NO current mission
--- ---
if asset.spawned then if asset.spawned then
@ -703,7 +893,8 @@ function SQUADRON:RecruitAssets(Mission)
if Mission.type==AUFTRAG.Type.INTERCEPT then if Mission.type==AUFTRAG.Type.INTERCEPT then
combatready=flightgroup:CanAirToAir() combatready=flightgroup:CanAirToAir()
else else
combatready=flightgroup:CanAirToGround() local excludeguns=Mission.type==AUFTRAG.Type.BOMBING or Mission.type==AUFTRAG.Type.BOMBRUNWAY or Mission.type==AUFTRAG.Type.BOMBCARPET or Mission.type==AUFTRAG.Type.SEAD or Mission.type==AUFTRAG.Type.ANTISHIP
combatready=flightgroup:CanAirToGround(excludeguns)
end end
-- No more attacks if fuel is already low. Safety first! -- No more attacks if fuel is already low. Safety first!
@ -712,7 +903,7 @@ function SQUADRON:RecruitAssets(Mission)
end end
-- Check if in a state where we really do not want to fight any more. -- Check if in a state where we really do not want to fight any more.
if flightgroup:IsLanding() or flightgroup:IsLanded() or flightgroup:IsArrived() or flightgroup:IsDead() then if flightgroup:IsHolding() or flightgroup:IsLanding() or flightgroup:IsLanded() or flightgroup:IsArrived() or flightgroup:IsDead() or flightgroup:IsStopped() then
combatready=false combatready=false
end end
@ -731,7 +922,7 @@ function SQUADRON:RecruitAssets(Mission)
--- ---
-- Check that asset is not already requested for another mission. -- Check that asset is not already requested for another mission.
if Npayloads>0 and not asset.requested then if Npayloads>0 and self:IsRepaired(asset) and (not asset.requested) then
-- Add this asset to the selection. -- Add this asset to the selection.
table.insert(assets, asset) table.insert(assets, asset)
@ -749,6 +940,51 @@ function SQUADRON:RecruitAssets(Mission)
end end
--- Get the time an asset needs to be repaired.
-- @param #SQUADRON self
-- @param Ops.AirWing#AIRWING.SquadronAsset Asset The asset.
-- @return #number Time in seconds until asset is repaired.
function SQUADRON:GetRepairTime(Asset)
if Asset.Treturned then
local t=self.maintenancetime
t=t+Asset.damage*self.repairtime
-- Seconds after returned.
local dt=timer.getAbsTime()-Asset.Treturned
local T=t-dt
return T
else
return 0
end
end
--- Checks if a mission type is contained in a table of possible types.
-- @param #SQUADRON self
-- @param Ops.AirWing#AIRWING.SquadronAsset Asset The asset.
-- @return #boolean If true, the requested mission type is part of the possible mission types.
function SQUADRON:IsRepaired(Asset)
if Asset.Treturned then
local Tnow=timer.getAbsTime()
local Trepaired=Asset.Treturned+self.maintenancetime
if Tnow>=Trepaired then
return true
else
return false
end
else
return true
end
end
--- Checks if a mission type is contained in a table of possible types. --- Checks if a mission type is contained in a table of possible types.
-- @param #SQUADRON self -- @param #SQUADRON self
-- @param #string MissionType The requested mission type. -- @param #string MissionType The requested mission type.

File diff suppressed because it is too large Load Diff

View File

@ -17,6 +17,7 @@
-- @field #table CategoryName Names of airbase categories. -- @field #table CategoryName Names of airbase categories.
-- @field #string AirbaseName Name of the airbase. -- @field #string AirbaseName Name of the airbase.
-- @field #number AirbaseID Airbase ID. -- @field #number AirbaseID Airbase ID.
-- @field Core.Zone#ZONE AirbaseZone Circular zone around the airbase with a radius of 2500 meters. For ships this is a ZONE_UNIT object.
-- @field #number category Airbase category. -- @field #number category Airbase category.
-- @field #table descriptors DCS descriptors. -- @field #table descriptors DCS descriptors.
-- @field #boolean isAirdrome Airbase is an airdrome. -- @field #boolean isAirdrome Airbase is an airdrome.
@ -493,8 +494,14 @@ function AIRBASE:Register(AirbaseName)
self:GetCoordinate() self:GetCoordinate()
if vec2 then if vec2 then
-- TODO: For ships we need a moving zone. if self.isShip then
local unit=UNIT:FindByName(AirbaseName)
if unit then
self.AirbaseZone=ZONE_UNIT:New(AirbaseName, unit, 2500)
end
else
self.AirbaseZone=ZONE_RADIUS:New(AirbaseName, vec2, 2500) self.AirbaseZone=ZONE_RADIUS:New(AirbaseName, vec2, 2500)
end
else else
self:E(string.format("ERROR: Cound not get position Vec2 of airbase %s", AirbaseName)) self:E(string.format("ERROR: Cound not get position Vec2 of airbase %s", AirbaseName))
end end

View File

@ -814,7 +814,8 @@ end
-- @return #number The velocity in knots. -- @return #number The velocity in knots.
function POSITIONABLE:GetVelocityKNOTS() function POSITIONABLE:GetVelocityKNOTS()
self:F2( self.PositionableName ) self:F2( self.PositionableName )
return UTILS.MpsToKnots(self:GetVelocityMPS()) local velmps=self:GetVelocityMPS()
return UTILS.MpsToKnots(velmps)
end end
--- Returns the Angle of Attack of a positionable. --- Returns the Angle of Attack of a positionable.