#Changes from Develop

This commit is contained in:
Applevangelist 2022-09-10 11:49:40 +02:00
parent c58e91b956
commit 7c22e9fe69
48 changed files with 7792 additions and 3739 deletions

View File

@ -0,0 +1,943 @@
--- **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!*
--
-- ===
--
-- # 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 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:SetValidNeighbourRoad(MaxDistance)
self:SetValidNeighbourFunction(ASTAR.Road, 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
--- Set heuristic cost to go from one node to another to be their 3D distance.
-- @param #ASTAR self
-- @return #ASTAR self
function ASTAR:SetCostRoad()
self:SetCostFunction(ASTAR)
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:T(self.lid..text)
-- 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:T2(self.lid..text)
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 two nodes have a road connection.
-- @param #ASTAR.Node nodeA First node.
-- @param #ASTAR.Node nodeB Other node.
-- @return #boolean If true, two nodes are connected via a road.
function ASTAR.Road(nodeA, nodeB)
local path=land.findPathOnRoads("roads", nodeA.coordinate.x, nodeA.coordinate.z, nodeB.coordinate.x, nodeB.coordinate.z)
if path then
return true
else
return false
end
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)
local dist=nodeA.coordinate:Get2DDistance(nodeB)
return dist
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)
local dist=nodeA.coordinate:Get3DDistance(nodeB.coordinate)
return dist
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)
-- Get the path.
local path=land.findPathOnRoads("roads", nodeA.coordinate.x, nodeA.coordinate.z, nodeB.coordinate.x, nodeB.coordinate.z)
if path then
local dist=0
for i=2,#path do
local b=path[i] --DCS#Vec2
local a=path[i-1] --DCS#Vec2
dist=dist+UTILS.VecDist2D(a,b)
end
return dist
end
return math.huge
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:T(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:T(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:T(self.lid..text)
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:T(self.lid..text)
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

@ -229,7 +229,8 @@ FORMATION = {
-- @param #BASE self -- @param #BASE self
-- @return #BASE -- @return #BASE
function BASE:New() function BASE:New()
local self = routines.utils.deepCopy( self ) -- Create a new self instance --local self = routines.utils.deepCopy( self ) -- Create a new self instance
local self = UTILS.DeepCopy(self)
_ClassID = _ClassID + 1 _ClassID = _ClassID + 1
self.ClassID = _ClassID self.ClassID = _ClassID
@ -463,131 +464,152 @@ do -- Event Handling
return self return self
end end
-- Event handling function prototypes -- Event handling function prototypes - Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
--- Occurs whenever any unit in a mission fires a weapon. But not any machine gun or autocannon based weapon, those are handled by EVENT.ShootingStart. --- Occurs whenever any unit in a mission fires a weapon. But not any machine gun or autocannon based weapon, those are handled by EVENT.ShootingStart.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventShot -- @function [parent=#BASE] OnEventShot
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs whenever an object is hit by a weapon. --- Occurs whenever an object is hit by a weapon.
-- initiator : The unit object the fired the weapon. -- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- weapon: Weapon object that hit the target. -- initiator : The unit object the fired the weapon
-- weapon: Weapon object that hit the target
-- target: The Object that was hit. -- target: The Object that was hit.
-- @function [parent=#BASE] OnEventHit -- @function [parent=#BASE] OnEventHit
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when an aircraft takes off from an airbase, farp, or ship. --- Occurs when an aircraft takes off from an airbase, farp, or ship.
-- initiator : The unit that took off. -- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- place: Object from where the AI took-off from. Can be an Airbase Object, FARP, or Ships. -- initiator : The unit that tookoff
-- place: Object from where the AI took-off from. Can be an Airbase Object, FARP, or Ships
-- @function [parent=#BASE] OnEventTakeoff -- @function [parent=#BASE] OnEventTakeoff
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when an aircraft lands at an airbase, farp or ship --- Occurs when an aircraft lands at an airbase, farp or ship
-- initiator : The unit that has landed. -- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- place: Object that the unit landed on. Can be an Airbase Object, FARP, or Ships. -- initiator : The unit that has landed
-- place: Object that the unit landed on. Can be an Airbase Object, FARP, or Ships
-- @function [parent=#BASE] OnEventLand -- @function [parent=#BASE] OnEventLand
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when any aircraft crashes into the ground and is completely destroyed. --- Occurs when any aircraft crashes into the ground and is completely destroyed.
-- initiator : The unit that has crashed. -- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that has crashed
-- @function [parent=#BASE] OnEventCrash -- @function [parent=#BASE] OnEventCrash
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when a pilot ejects from an aircraft --- Occurs when a pilot ejects from an aircraft
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that has ejected -- initiator : The unit that has ejected
-- @function [parent=#BASE] OnEventEjection -- @function [parent=#BASE] OnEventEjection
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when an aircraft connects with a tanker and begins taking on fuel. --- Occurs when an aircraft connects with a tanker and begins taking on fuel.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that is receiving fuel. -- initiator : The unit that is receiving fuel.
-- @function [parent=#BASE] OnEventRefueling -- @function [parent=#BASE] OnEventRefueling
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when an object is dead. --- Occurs when an object is dead.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that is dead. -- initiator : The unit that is dead.
-- @function [parent=#BASE] OnEventDead -- @function [parent=#BASE] OnEventDead
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when an object is completely destroyed. --- Occurs when an Event for an object is triggered.
-- initiator : The unit that is was destroyed. -- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that triggered the event.
-- @function [parent=#BASE] OnEvent -- @function [parent=#BASE] OnEvent
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when the pilot of an aircraft is killed. Can occur either if the player is alive and crashes or if a weapon kills the pilot without completely destroying the plane. --- Occurs when the pilot of an aircraft is killed. Can occur either if the player is alive and crashes or if a weapon kills the pilot without completely destroying the plane.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that the pilot has died in. -- initiator : The unit that the pilot has died in.
-- @function [parent=#BASE] OnEventPilotDead -- @function [parent=#BASE] OnEventPilotDead
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when a ground unit captures either an airbase or a farp. --- Occurs when a ground unit captures either an airbase or a farp.
-- initiator : The unit that captured the base. -- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that captured the base
-- place: The airbase that was captured, can be a FARP or Airbase. When calling place:getCoalition() the faction will already be the new owning faction. -- place: The airbase that was captured, can be a FARP or Airbase. When calling place:getCoalition() the faction will already be the new owning faction.
-- @function [parent=#BASE] OnEventBaseCaptured -- @function [parent=#BASE] OnEventBaseCaptured
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when a mission starts. --- Occurs when a mission starts
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventMissionStart -- @function [parent=#BASE] OnEventMissionStart
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when a mission ends. --- Occurs when a mission ends
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventMissionEnd -- @function [parent=#BASE] OnEventMissionEnd
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when an aircraft is finished taking fuel. --- Occurs when an aircraft is finished taking fuel.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that was receiving fuel. -- initiator : The unit that was receiving fuel.
-- @function [parent=#BASE] OnEventRefuelingStop -- @function [parent=#BASE] OnEventRefuelingStop
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when any object is spawned into the mission. --- Occurs when any object is spawned into the mission.
-- initiator : The unit that was spawned. -- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that was spawned
-- @function [parent=#BASE] OnEventBirth -- @function [parent=#BASE] OnEventBirth
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when any system fails on a human controlled aircraft. --- Occurs when any system fails on a human controlled aircraft.
-- initiator : The unit that had the failure. -- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that had the failure
-- @function [parent=#BASE] OnEventHumanFailure -- @function [parent=#BASE] OnEventHumanFailure
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when any aircraft starts its engines. --- Occurs when any aircraft starts its engines.
-- initiator : The unit that is starting its engines.. -- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that is starting its engines.
-- @function [parent=#BASE] OnEventEngineStartup -- @function [parent=#BASE] OnEventEngineStartup
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when any aircraft shuts down its engines. --- Occurs when any aircraft shuts down its engines.
-- initiator : The unit that is stopping its engines.. -- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that is stopping its engines.
-- @function [parent=#BASE] OnEventEngineShutdown -- @function [parent=#BASE] OnEventEngineShutdown
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when any player assumes direct control of a unit. --- Occurs when any player assumes direct control of a unit. Note - not Mulitplayer safe. Use PlayerEnterAircraft.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that is being taken control of. -- initiator : The unit that is being taken control of.
-- @function [parent=#BASE] OnEventPlayerEnterUnit -- @function [parent=#BASE] OnEventPlayerEnterUnit
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when any player relieves control of a unit to the AI. --- Occurs when any player relieves control of a unit to the AI.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that the player left. -- initiator : The unit that the player left.
-- @function [parent=#BASE] OnEventPlayerLeaveUnit -- @function [parent=#BASE] OnEventPlayerLeaveUnit
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when any unit begins firing a weapon that has a high rate of fire. Most common with aircraft cannons (GAU-8), autocannons, and machine guns. --- Occurs when any unit begins firing a weapon that has a high rate of fire. Most common with aircraft cannons (GAU-8), autocannons, and machine guns.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that is doing the shooting. -- initiator : The unit that is doing the shooting.
-- target: The unit that is being targeted. -- target: The unit that is being targeted.
-- @function [parent=#BASE] OnEventShootingStart -- @function [parent=#BASE] OnEventShootingStart
@ -595,24 +617,28 @@ do -- Event Handling
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when any unit stops firing its weapon. Event will always correspond with a shooting start event. --- Occurs when any unit stops firing its weapon. Event will always correspond with a shooting start event.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- initiator : The unit that was doing the shooting. -- initiator : The unit that was doing the shooting.
-- @function [parent=#BASE] OnEventShootingEnd -- @function [parent=#BASE] OnEventShootingEnd
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when a new mark was added. --- Occurs when a new mark was added.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- MarkID: ID of the mark. -- MarkID: ID of the mark.
-- @function [parent=#BASE] OnEventMarkAdded -- @function [parent=#BASE] OnEventMarkAdded
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when a mark was removed. --- Occurs when a mark was removed.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- MarkID: ID of the mark. -- MarkID: ID of the mark.
-- @function [parent=#BASE] OnEventMarkRemoved -- @function [parent=#BASE] OnEventMarkRemoved
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when a mark text was changed. --- Occurs when a mark text was changed.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- MarkID: ID of the mark. -- MarkID: ID of the mark.
-- @function [parent=#BASE] OnEventMarkChange -- @function [parent=#BASE] OnEventMarkChange
-- @param #BASE self -- @param #BASE self
@ -628,13 +654,15 @@ do -- Event Handling
--- Occurs when any modification to the "Score" as seen on the debrief menu would occur. --- Occurs when any modification to the "Score" as seen on the debrief menu would occur.
-- There is no information on what values the score was changed to. Event is likely similar to player_comment in this regard. -- There is no information on what values the score was changed to. Event is likely similar to player_comment in this regard.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventScore -- @function [parent=#BASE] OnEventScore
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs on the death of a unit. Contains more and different information. Similar to unit_lost it will occur for aircraft before the aircraft crash event occurs. --- Occurs on the death of a unit. Contains more and different information. Similar to unit_lost it will occur for aircraft before the aircraft crash event occurs.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- --
-- * initiator: The unit that killed the target. -- * initiator: The unit that killed the target
-- * target: Target Object -- * target: Target Object
-- * weapon: Weapon Object -- * weapon: Weapon Object
-- --
@ -644,11 +672,13 @@ do -- Event Handling
--- Occurs when any modification to the "Score" as seen on the debrief menu would occur. --- Occurs when any modification to the "Score" as seen on the debrief menu would occur.
-- There is no information on what values the score was changed to. Event is likely similar to player_comment in this regard. -- There is no information on what values the score was changed to. Event is likely similar to player_comment in this regard.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventScore -- @function [parent=#BASE] OnEventScore
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when the game thinks an object is destroyed. --- Occurs when the game thinks an object is destroyed.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- --
-- * initiator: The unit that is was destroyed. -- * initiator: The unit that is was destroyed.
-- --
@ -657,6 +687,7 @@ do -- Event Handling
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs shortly after the landing animation of an ejected pilot touching the ground and standing up. Event does not occur if the pilot lands in the water and sub combs to Davey Jones Locker. --- Occurs shortly after the landing animation of an ejected pilot touching the ground and standing up. Event does not occur if the pilot lands in the water and sub combs to Davey Jones Locker.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- --
-- * initiator: Static object representing the ejected pilot. Place : Aircraft that the pilot ejected from. -- * initiator: Static object representing the ejected pilot. Place : Aircraft that the pilot ejected from.
-- * place: may not return as a valid object if the aircraft has crashed into the ground and no longer exists. -- * place: may not return as a valid object if the aircraft has crashed into the ground and no longer exists.
@ -667,36 +698,43 @@ do -- Event Handling
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Paratrooper landing. --- Paratrooper landing.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventParatrooperLanding -- @function [parent=#BASE] OnEventParatrooperLanding
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Discard chair after ejection. --- Discard chair after ejection.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventDiscardChairAfterEjection -- @function [parent=#BASE] OnEventDiscardChairAfterEjection
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Weapon add. Fires when entering a mission per pylon with the name of the weapon (double pylons not counted, infinite wep reload not counted. --- Weapon add. Fires when entering a mission per pylon with the name of the weapon (double pylons not counted, infinite wep reload not counted.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventParatrooperLanding -- @function [parent=#BASE] OnEventParatrooperLanding
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Trigger zone. --- Trigger zone.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventTriggerZone -- @function [parent=#BASE] OnEventTriggerZone
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Landing quality mark. --- Landing quality mark.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventLandingQualityMark -- @function [parent=#BASE] OnEventLandingQualityMark
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- BDA. --- BDA.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- @function [parent=#BASE] OnEventBDA -- @function [parent=#BASE] OnEventBDA
-- @param #BASE self -- @param #BASE self
-- @param Core.Event#EVENTDATA EventData The EventData structure. -- @param Core.Event#EVENTDATA EventData The EventData structure.
--- Occurs when a player enters a slot and takes control of an aircraft. --- Occurs when a player enters a slot and takes control of an aircraft.
-- Have a look at the class @{Core.EVENT#EVENT} as these are just the prototypes.
-- **NOTE**: This is a workaround of a long standing DCS bug with the PLAYER_ENTER_UNIT event. -- **NOTE**: This is a workaround of a long standing DCS bug with the PLAYER_ENTER_UNIT event.
-- initiator : The unit that is being taken control of. -- initiator : The unit that is being taken control of.
-- @function [parent=#BASE] OnEventPlayerEnterAircraft -- @function [parent=#BASE] OnEventPlayerEnterAircraft
@ -744,17 +782,34 @@ function BASE:CreateEventCrash( EventTime, Initiator, IniObjectCategory )
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.
-- @param DCS#Object Initiator The initiating object of the event. -- @param DCS#Object Initiator The initiating object of the event.
function BASE:CreateEventDead( EventTime, Initiator ) function BASE:CreateEventDead( EventTime, Initiator, IniObjectCategory )
self:F( { EventTime, Initiator } ) self:F( { EventTime, Initiator, IniObjectCategory } )
local Event = { local Event = {
id = world.event.S_EVENT_DEAD, id = world.event.S_EVENT_DEAD,
time = EventTime, time = EventTime,
initiator = Initiator, initiator = Initiator,
IniObjectCategory = IniObjectCategory,
} }
world.onEvent( Event ) world.onEvent( Event )
@ -801,13 +856,12 @@ function BASE:CreateEventPlayerEnterAircraft( PlayerUnit )
local Event = { local Event = {
id = EVENTS.PlayerEnterAircraft, id = EVENTS.PlayerEnterAircraft,
time = timer.getTime(), time = timer.getTime(),
initiator = PlayerUnit:GetDCSObject(), initiator = PlayerUnit:GetDCSObject()
} }
world.onEvent(Event) world.onEvent(Event)
end end
-- TODO: Complete DCS#Event structure.
--- The main event handling function... This function captures all events generated for the class. --- The main event handling function... This function captures all events generated for the class.
-- @param #BASE self -- @param #BASE self
-- @param DCS#Event event -- @param DCS#Event event
@ -846,20 +900,22 @@ do -- Scheduling
-- @param #number Start Specifies the amount of seconds that will be waited before the scheduling is started, and the event function is called. -- @param #number Start Specifies the amount of seconds that will be waited before the scheduling is started, and the event function is called.
-- @param #function SchedulerFunction The event function to be called when a timer event occurs. The event function needs to accept the parameters specified in SchedulerArguments. -- @param #function SchedulerFunction The event function to be called when a timer event occurs. The event function needs to accept the parameters specified in SchedulerArguments.
-- @param #table ... Optional arguments that can be given as part of scheduler. The arguments need to be given as a table { param1, param 2, ... }. -- @param #table ... Optional arguments that can be given as part of scheduler. The arguments need to be given as a table { param1, param 2, ... }.
-- @return #number The ScheduleID of the planned schedule. -- @return #string The Schedule ID of the planned schedule.
function BASE:ScheduleOnce( Start, SchedulerFunction, ... ) function BASE:ScheduleOnce( Start, SchedulerFunction, ... )
self:F2( { Start } )
self:T3( { ... } )
-- Object name.
local ObjectName = "-" local ObjectName = "-"
ObjectName = self.ClassName .. self.ClassID ObjectName = self.ClassName .. self.ClassID
-- Debug info.
self:F3( { "ScheduleOnce: ", ObjectName, Start } ) self:F3( { "ScheduleOnce: ", ObjectName, Start } )
if not self.Scheduler then if not self.Scheduler then
self.Scheduler = SCHEDULER:New( self ) self.Scheduler = SCHEDULER:New( self )
end end
-- FF this was wrong!
--[[
local ScheduleID = _SCHEDULEDISPATCHER:AddSchedule( local ScheduleID = _SCHEDULEDISPATCHER:AddSchedule(
self, self,
SchedulerFunction, SchedulerFunction,
@ -869,6 +925,10 @@ do -- Scheduling
nil, nil,
nil nil
) )
]]
-- NOTE: MasterObject (first parameter) needs to be nil or it will be the first argument passed to the SchedulerFunction!
local ScheduleID = self.Scheduler:Schedule(nil, SchedulerFunction, {...}, Start)
self._.Schedules[#self._.Schedules+1] = ScheduleID self._.Schedules[#self._.Schedules+1] = ScheduleID
@ -883,7 +943,7 @@ do -- Scheduling
-- @param #number Stop Specifies the amount of seconds when the scheduler will be stopped. -- @param #number Stop Specifies the amount of seconds when the scheduler will be stopped.
-- @param #function SchedulerFunction The event function to be called when a timer event occurs. The event function needs to accept the parameters specified in SchedulerArguments. -- @param #function SchedulerFunction The event function to be called when a timer event occurs. The event function needs to accept the parameters specified in SchedulerArguments.
-- @param #table ... Optional arguments that can be given as part of scheduler. The arguments need to be given as a table { param1, param 2, ... }. -- @param #table ... Optional arguments that can be given as part of scheduler. The arguments need to be given as a table { param1, param 2, ... }.
-- @return #number The ScheduleID of the planned schedule. -- @return #string The Schedule ID of the planned schedule.
function BASE:ScheduleRepeat( Start, Repeat, RandomizeFactor, Stop, SchedulerFunction, ... ) function BASE:ScheduleRepeat( Start, Repeat, RandomizeFactor, Stop, SchedulerFunction, ... )
self:F2( { Start } ) self:F2( { Start } )
self:T3( { ... } ) self:T3( { ... } )
@ -897,8 +957,9 @@ do -- Scheduling
self.Scheduler = SCHEDULER:New( self ) self.Scheduler = SCHEDULER:New( self )
end end
-- NOTE: MasterObject (first parameter) should(!) be nil as it will be the first argument passed to the SchedulerFunction!
local ScheduleID = self.Scheduler:Schedule( local ScheduleID = self.Scheduler:Schedule(
self, nil,
SchedulerFunction, SchedulerFunction,
{ ... }, { ... },
Start, Start,
@ -915,13 +976,13 @@ do -- Scheduling
--- Stops the Schedule. --- Stops the Schedule.
-- @param #BASE self -- @param #BASE self
-- @param #function SchedulerFunction The event function to be called when a timer event occurs. The event function needs to accept the parameters specified in SchedulerArguments. -- @param #string SchedulerID (Optional) Scheduler ID to be stopped. If nil, all pending schedules are stopped.
function BASE:ScheduleStop( SchedulerFunction ) function BASE:ScheduleStop( SchedulerID )
self:F3( { "ScheduleStop:" } ) self:F3( { "ScheduleStop:" } )
if self.Scheduler then if self.Scheduler then
_SCHEDULEDISPATCHER:Stop( self.Scheduler, self._.Schedules[SchedulerFunction] ) --_SCHEDULEDISPATCHER:Stop( self.Scheduler, self._.Schedules[SchedulerFunction] )
_SCHEDULEDISPATCHER:Stop(self.Scheduler, SchedulerID)
end end
end end
@ -1062,7 +1123,7 @@ end
--- Set tracing for a class --- Set tracing for a class
-- @param #BASE self -- @param #BASE self
-- @param #string Class -- @param #string Class Class name.
function BASE:TraceClass( Class ) function BASE:TraceClass( Class )
_TraceClass[Class] = true _TraceClass[Class] = true
_TraceClassMethod[Class] = {} _TraceClassMethod[Class] = {}
@ -1071,8 +1132,8 @@ end
--- Set tracing for a specific method of class --- Set tracing for a specific method of class
-- @param #BASE self -- @param #BASE self
-- @param #string Class -- @param #string Class Class name.
-- @param #string Method -- @param #string Method Method.
function BASE:TraceClassMethod( Class, Method ) function BASE:TraceClassMethod( Class, Method )
if not _TraceClassMethod[Class] then if not _TraceClassMethod[Class] then
_TraceClassMethod[Class] = {} _TraceClassMethod[Class] = {}

View File

@ -17,7 +17,7 @@
-- --
-- After attaching a @{#BEACON} to your @{Wrapper.Positionable#POSITIONABLE}, you need to select the right function to activate the kind of beacon you want. -- After attaching a @{#BEACON} to your @{Wrapper.Positionable#POSITIONABLE}, you need to select the right function to activate the kind of beacon you want.
-- There are two types of BEACONs available : the (aircraft) TACAN Beacon and the general purpose Radio Beacon. -- There are two types of BEACONs available : the (aircraft) TACAN Beacon and the general purpose Radio Beacon.
-- Note that in both case, you can set an optional parameter : the `BeaconDuration`. This can be very useful to simulate the battery time if your BEACON is -- Note that in both case, you can set an optional parameter : the `BeaconDuration`. This can be very usefull to simulate the battery time if your BEACON is
-- attach to a cargo crate, for exemple. -- attach to a cargo crate, for exemple.
-- --
-- ## Aircraft TACAN Beacon usage -- ## Aircraft TACAN Beacon usage
@ -265,13 +265,12 @@ function BEACON:ActivateLink4(Frequency, Morse, Duration)
-- Stop sheduler -- Stop sheduler
if Duration then -- Schedule the stop of the BEACON if asked by the MD if Duration then -- Schedule the stop of the BEACON if asked by the MD
self.Positionable:DeactivateLink4(Duration) self.Positionable:CommandDeactivateLink4(Duration)
end end
return self return self
end end
--- DEPRECATED: Please use @{BEACON:ActivateTACAN}() instead. --- DEPRECATED: Please use @{BEACON:ActivateTACAN}() instead.
-- Activates a TACAN BEACON on an Aircraft. -- Activates a TACAN BEACON on an Aircraft.
-- @param #BEACON self -- @param #BEACON self
@ -430,7 +429,7 @@ function BEACON:RadioBeacon(FileName, Frequency, Modulation, Power, BeaconDurati
end end
end end
--- Stop the Radio Beacon --- Stops the Radio Beacon
-- @param #BEACON self -- @param #BEACON self
-- @return #BEACON self -- @return #BEACON self
function BEACON:StopRadioBeacon() function BEACON:StopRadioBeacon()

View File

@ -0,0 +1,295 @@
--- **Core** - Define any or all conditions to be evaluated.
--
-- **Main Features:**
--
-- * Add arbitrary numbers of conditon functions
-- * Evaluate *any* or *all* conditions
--
-- ===
--
-- ## Example Missions:
--
-- Demo missions can be found on [github](https://github.com/FlightControl-Master/MOOSE_MISSIONS/tree/develop/OPS%20-%20Operation).
--
-- ===
--
-- ### Author: **funkyfranky**
--
-- ===
-- @module Core.Condition
-- @image Core_Conditon.png
--- CONDITON class.
-- @type CONDITION
-- @field #string ClassName Name of the class.
-- @field #string lid Class id string for output to DCS log file.
-- @field #boolean isAny General functions are evaluated as any condition.
-- @field #boolean negateResult Negeate result of evaluation.
-- @field #table functionsGen General condition functions.
-- @field #table functionsAny Any condition functions.
-- @field #table functionsAll All condition functions.
--
-- @extends Core.Base#BASE
--- *Better three hours too soon than a minute too late.* - William Shakespeare
--
-- ===
--
-- # The CONDITION Concept
--
--
--
-- @field #CONDITION
CONDITION = {
ClassName = "CONDITION",
lid = nil,
functionsGen = {},
functionsAny = {},
functionsAll = {},
}
--- Condition function.
-- @type CONDITION.Function
-- @field #function func Callback function to check for a condition. Should return a `#boolean`.
-- @field #table arg (Optional) Arguments passed to the condition callback function if any.
--- CONDITION class version.
-- @field #string version
CONDITION.version="0.1.0"
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO list
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO: Make FSM.
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Constructor
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Create a new CONDITION object.
-- @param #CONDITION self
-- @param #string Name (Optional) Name used in the logs.
-- @return #CONDITION self
function CONDITION:New(Name)
-- Inherit BASE.
local self=BASE:Inherit(self, BASE:New()) --#CONDITION
self.name=Name or "Condition X"
self.lid=string.format("%s | ", self.name)
return self
end
--- Set that general condition functions return `true` if `any` function returns `true`. Default is that *all* functions must return `true`.
-- @param #CONDITION self
-- @param #boolean Any If `true`, *any* condition can be true. Else *all* conditions must result `true`.
-- @return #CONDITION self
function CONDITION:SetAny(Any)
self.isAny=Any
return self
end
--- Negate result.
-- @param #CONDITION self
-- @param #boolean Negate If `true`, result is negated else not.
-- @return #CONDITION self
function CONDITION:SetNegateResult(Negate)
self.negateResult=Negate
return self
end
--- Add a function that is evaluated. It must return a `#boolean` value, *i.e.* either `true` or `false` (or `nil`).
-- @param #CONDITION self
-- @param #function Function The function to call.
-- @param ... (Optional) Parameters passed to the function (if any).
--
-- @usage
-- local function isAequalB(a, b)
-- return a==b
-- end
--
-- myCondition:AddFunction(isAequalB, a, b)
--
-- @return #CONDITION self
function CONDITION:AddFunction(Function, ...)
-- Condition function.
local condition=self:_CreateCondition(Function, ...)
-- Add to table.
table.insert(self.functionsGen, condition)
return self
end
--- Add a function that is evaluated. It must return a `#boolean` value, *i.e.* either `true` or `false` (or `nil`).
-- @param #CONDITION self
-- @param #function Function The function to call.
-- @param ... (Optional) Parameters passed to the function (if any).
-- @return #CONDITION self
function CONDITION:AddFunctionAny(Function, ...)
-- Condition function.
local condition=self:_CreateCondition(Function, ...)
-- Add to table.
table.insert(self.functionsAny, condition)
return self
end
--- Add a function that is evaluated. It must return a `#boolean` value, *i.e.* either `true` or `false` (or `nil`).
-- @param #CONDITION self
-- @param #function Function The function to call.
-- @param ... (Optional) Parameters passed to the function (if any).
-- @return #CONDITION self
function CONDITION:AddFunctionAll(Function, ...)
-- Condition function.
local condition=self:_CreateCondition(Function, ...)
-- Add to table.
table.insert(self.functionsAll, condition)
return self
end
--- Evaluate conditon functions.
-- @param #CONDITION self
-- @param #boolean AnyTrue If `true`, evaluation return `true` if *any* condition function returns `true`. By default, *all* condition functions must return true.
-- @return #boolean Result of condition functions.
function CONDITION:Evaluate(AnyTrue)
-- Check if at least one function was given.
if #self.functionsAll + #self.functionsAny + #self.functionsAll == 0 then
if self.negateResult then
return true
else
return false
end
end
-- Any condition for gen.
local evalAny=self.isAny
if AnyTrue~=nil then
evalAny=AnyTrue
end
local isGen=nil
if evalAny then
isGen=self:_EvalConditionsAny(self.functionsGen)
else
isGen=self:_EvalConditionsAll(self.functionsGen)
end
-- Is any?
local isAny=self:_EvalConditionsAny(self.functionsAny)
-- Is all?
local isAll=self:_EvalConditionsAll(self.functionsAll)
-- Result.
local result=isGen and isAny and isAll
-- Negate result.
if self.negateResult then
result=not result
end
-- Debug message.
self:T(self.lid..string.format("Evaluate: isGen=%s, isAny=%s, isAll=%s (negate=%s) ==> result=%s", tostring(isGen), tostring(isAny), tostring(isAll), tostring(self.negateResult), tostring(result)))
return result
end
--- Check if all given condition are true.
-- @param #CONDITION self
-- @param #table functions Functions to evaluate.
-- @return #boolean If true, all conditions were true (or functions was empty/nil). Returns false if at least one condition returned false.
function CONDITION:_EvalConditionsAll(functions)
-- At least one condition?
local gotone=false
-- Any stop condition must be true.
for _,_condition in pairs(functions or {}) do
local condition=_condition --#CONDITION.Function
-- At least one condition was defined.
gotone=true
-- Call function.
local istrue=condition.func(unpack(condition.arg))
-- Any false will return false.
if not istrue then
return false
end
end
-- All conditions were true.
return true
end
--- Check if any of the given conditions is true.
-- @param #CONDITION self
-- @param #table functions Functions to evaluate.
-- @return #boolean If true, at least one condition is true (or functions was emtpy/nil).
function CONDITION:_EvalConditionsAny(functions)
-- At least one condition?
local gotone=false
-- Any stop condition must be true.
for _,_condition in pairs(functions or {}) do
local condition=_condition --#CONDITION.Function
-- At least one condition was defined.
gotone=true
-- Call function.
local istrue=condition.func(unpack(condition.arg))
-- Any true will return true.
if istrue then
return true
end
end
-- No condition was true.
if gotone then
return false
else
-- No functions passed.
return true
end
end
--- Create conditon function object.
-- @param #CONDITION self
-- @param #function Function The function to call.
-- @param ... (Optional) Parameters passed to the function (if any).
-- @return #CONDITION.Function Condition function.
function CONDITION:_CreateCondition(Function, ...)
local condition={} --#CONDITION.Function
condition.func=Function
condition.arg={}
if arg then
condition.arg=arg
end
return condition
end
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------

View File

@ -31,6 +31,7 @@
-- @module Core.Database -- @module Core.Database
-- @image Core_Database.JPG -- @image Core_Database.JPG
--- @type DATABASE --- @type DATABASE
-- @field #string ClassName Name of the class. -- @field #string ClassName Name of the class.
-- @field #table Templates Templates: Units, Groups, Statics, ClientsByName, ClientsByID. -- @field #table Templates Templates: Units, Groups, Statics, ClientsByName, ClientsByID.
@ -50,7 +51,7 @@
-- * PLAYERS -- * PLAYERS
-- * CARGOS -- * CARGOS
-- --
-- On top, for internal MOOSE administration purposes, the DATABASE administers the Unit and Group TEMPLATES as defined within the Mission Editor. -- On top, for internal MOOSE administration purposes, the DATBASE administers the Unit and Group TEMPLATES as defined within the Mission Editor.
-- --
-- The singleton object **_DATABASE** is automatically created by MOOSE, that administers all objects within the mission. -- The singleton object **_DATABASE** is automatically created by MOOSE, that administers all objects within the mission.
-- Moose refers to **_DATABASE** within the framework extensively, but you can also refer to the _DATABASE object within your missions if required. -- Moose refers to **_DATABASE** within the framework extensively, but you can also refer to the _DATABASE object within your missions if required.
@ -89,13 +90,15 @@ DATABASE = {
FLIGHTCONTROLS = {}, FLIGHTCONTROLS = {},
} }
local _DATABASECoalition = { local _DATABASECoalition =
{
[1] = "Red", [1] = "Red",
[2] = "Blue", [2] = "Blue",
[3] = "Neutral", [3] = "Neutral",
} }
local _DATABASECategory = { local _DATABASECategory =
{
["plane"] = Unit.Category.AIRPLANE, ["plane"] = Unit.Category.AIRPLANE,
["helicopter"] = Unit.Category.HELICOPTER, ["helicopter"] = Unit.Category.HELICOPTER,
["vehicle"] = Unit.Category.GROUND_UNIT, ["vehicle"] = Unit.Category.GROUND_UNIT,
@ -103,6 +106,7 @@ local _DATABASECategory = {
["static"] = Unit.Category.STRUCTURE, ["static"] = Unit.Category.STRUCTURE,
} }
--- Creates a new DATABASE object, building a set of units belonging to a coalitions, categories, countries, types or with defined prefix names. --- Creates a new DATABASE object, building a set of units belonging to a coalitions, categories, countries, types or with defined prefix names.
-- @param #DATABASE self -- @param #DATABASE self
-- @return #DATABASE -- @return #DATABASE
@ -120,6 +124,7 @@ function DATABASE:New()
self:HandleEvent( EVENTS.Dead, self._EventOnDeadOrCrash ) self:HandleEvent( EVENTS.Dead, self._EventOnDeadOrCrash )
self:HandleEvent( EVENTS.Crash, self._EventOnDeadOrCrash ) self:HandleEvent( EVENTS.Crash, self._EventOnDeadOrCrash )
self:HandleEvent( EVENTS.RemoveUnit, self._EventOnDeadOrCrash ) self:HandleEvent( EVENTS.RemoveUnit, self._EventOnDeadOrCrash )
--self:HandleEvent( EVENTS.UnitLost, self._EventOnDeadOrCrash ) -- DCS 2.7.1 for Aerial units no dead event ATM
self:HandleEvent( EVENTS.Hit, self.AccountHits ) self:HandleEvent( EVENTS.Hit, self.AccountHits )
self:HandleEvent( EVENTS.NewCargo ) self:HandleEvent( EVENTS.NewCargo )
self:HandleEvent( EVENTS.DeleteCargo ) self:HandleEvent( EVENTS.DeleteCargo )
@ -132,8 +137,8 @@ function DATABASE:New()
self:_RegisterGroupsAndUnits() self:_RegisterGroupsAndUnits()
self:_RegisterClients() self:_RegisterClients()
self:_RegisterStatics() self:_RegisterStatics()
-- self:_RegisterAirbases()
--self:_RegisterPlayers() --self:_RegisterPlayers()
--self:_RegisterAirbases()
self.UNITS_Position = 0 self.UNITS_Position = 0
@ -150,6 +155,7 @@ function DATABASE:FindUnit( UnitName )
return UnitFound return UnitFound
end end
--- Adds a Unit based on the Unit Name in the DATABASE. --- Adds a Unit based on the Unit Name in the DATABASE.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string DCSUnitName Unit name. -- @param #string DCSUnitName Unit name.
@ -157,26 +163,20 @@ end
function DATABASE:AddUnit( DCSUnitName ) function DATABASE:AddUnit( DCSUnitName )
if not self.UNITS[DCSUnitName] then if not self.UNITS[DCSUnitName] then
-- Debug info. -- Debug info.
self:T( { "Add UNIT:", DCSUnitName } ) self:T( { "Add UNIT:", DCSUnitName } )
-- local UnitRegister = UNIT:Register( DCSUnitName )
-- Register unit -- Register unit
self.UNITS[DCSUnitName]=UNIT:Register(DCSUnitName) self.UNITS[DCSUnitName]=UNIT:Register(DCSUnitName)
-- This is not used anywhere in MOOSE as far as I can see so I remove it until there comes an error somewhere.
-- table.insert(self.UNITS_Index, DCSUnitName )
end end
return self.UNITS[DCSUnitName] return self.UNITS[DCSUnitName]
end end
--- Deletes a Unit from the DATABASE based on the Unit Name. --- Deletes a Unit from the DATABASE based on the Unit Name.
-- @param #DATABASE self -- @param #DATABASE self
function DATABASE:DeleteUnit( DCSUnitName ) function DATABASE:DeleteUnit( DCSUnitName )
self.UNITS[DCSUnitName] = nil self.UNITS[DCSUnitName] = nil
end end
@ -194,6 +194,7 @@ function DATABASE:AddStatic( DCSStaticName )
return nil return nil
end end
--- Deletes a Static from the DATABASE based on the Static Name. --- Deletes a Static from the DATABASE based on the Static Name.
-- @param #DATABASE self -- @param #DATABASE self
function DATABASE:DeleteStatic( DCSStaticName ) function DATABASE:DeleteStatic( DCSStaticName )
@ -210,16 +211,6 @@ function DATABASE:FindStatic( StaticName )
return StaticFound return StaticFound
end end
--- Finds a AIRBASE based on the AirbaseName.
-- @param #DATABASE self
-- @param #string AirbaseName
-- @return Wrapper.Airbase#AIRBASE The found AIRBASE.
function DATABASE:FindAirbase( AirbaseName )
local AirbaseFound = self.AIRBASES[AirbaseName]
return AirbaseFound
end
--- Adds a Airbase based on the Airbase Name in the DATABASE. --- Adds a Airbase based on the Airbase Name in the DATABASE.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string AirbaseName The name of the airbase. -- @param #string AirbaseName The name of the airbase.
@ -233,6 +224,7 @@ function DATABASE:AddAirbase( AirbaseName )
return self.AIRBASES[AirbaseName] return self.AIRBASES[AirbaseName]
end end
--- Deletes a Airbase from the DATABASE based on the Airbase Name. --- Deletes a Airbase from the DATABASE based on the Airbase Name.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string AirbaseName The name of the airbase -- @param #string AirbaseName The name of the airbase
@ -241,6 +233,17 @@ function DATABASE:DeleteAirbase( AirbaseName )
self.AIRBASES[AirbaseName] = nil self.AIRBASES[AirbaseName] = nil
end end
--- Finds an AIRBASE based on the AirbaseName.
-- @param #DATABASE self
-- @param #string AirbaseName
-- @return Wrapper.Airbase#AIRBASE The found AIRBASE.
function DATABASE:FindAirbase( AirbaseName )
local AirbaseFound = self.AIRBASES[AirbaseName]
return AirbaseFound
end
do -- Zones do -- Zones
--- Finds a @{Zone} based on the zone name. --- Finds a @{Zone} based on the zone name.
@ -264,6 +267,7 @@ do -- Zones
end end
end end
--- Deletes a @{Zone} from the DATABASE based on the zone name. --- Deletes a @{Zone} from the DATABASE based on the zone name.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string ZoneName The name of the zone. -- @param #string ZoneName The name of the zone.
@ -272,6 +276,7 @@ do -- Zones
self.ZONES[ZoneName] = nil self.ZONES[ZoneName] = nil
end end
--- Private method that registers new ZONE_BASE derived objects within the DATABASE Object. --- Private method that registers new ZONE_BASE derived objects within the DATABASE Object.
-- @param #DATABASE self -- @param #DATABASE self
-- @return #DATABASE self -- @return #DATABASE self
@ -318,6 +323,20 @@ do -- Zones
-- Store color of zone. -- Store color of zone.
Zone.Color=color Zone.Color=color
-- Store zone ID.
Zone.ZoneID=ZoneData.zoneId
-- Store zone properties (if any)
local ZoneProperties = ZoneData.properties or nil
Zone.Properties = {}
if ZoneName and ZoneProperties then
for _,ZoneProp in ipairs(ZoneProperties) do
if ZoneProp.key then
Zone.Properties[ZoneProp.key] = ZoneProp.value
end
end
end
-- Store in DB. -- Store in DB.
self.ZONENAMES[ZoneName] = ZoneName self.ZONENAMES[ZoneName] = ZoneName
@ -355,6 +374,7 @@ do -- Zones
end end
end -- zone end -- zone
do -- Zone_Goal do -- Zone_Goal
@ -380,6 +400,7 @@ do -- Zone_Goal
end end
end end
--- Deletes a @{Zone} from the DATABASE based on the zone name. --- Deletes a @{Zone} from the DATABASE based on the zone name.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string ZoneName The name of the zone. -- @param #string ZoneName The name of the zone.
@ -401,6 +422,7 @@ do -- cargo
end end
end end
--- Deletes a Cargo from the DATABASE based on the Cargo Name. --- Deletes a Cargo from the DATABASE based on the Cargo Name.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string CargoName The name of the airbase -- @param #string CargoName The name of the airbase
@ -494,6 +516,7 @@ function DATABASE:FindClient( ClientName )
return ClientFound return ClientFound
end end
--- Adds a CLIENT based on the ClientName in the DATABASE. --- Adds a CLIENT based on the ClientName in the DATABASE.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string ClientName Name of the Client unit. -- @param #string ClientName Name of the Client unit.
@ -507,6 +530,7 @@ function DATABASE:AddClient( ClientName )
return self.CLIENTS[ClientName] return self.CLIENTS[ClientName]
end end
--- Finds a GROUP based on the GroupName. --- Finds a GROUP based on the GroupName.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string GroupName -- @param #string GroupName
@ -517,6 +541,7 @@ function DATABASE:FindGroup( GroupName )
return GroupFound return GroupFound
end end
--- Adds a GROUP based on the GroupName in the DATABASE. --- Adds a GROUP based on the GroupName in the DATABASE.
-- @param #DATABASE self -- @param #DATABASE self
function DATABASE:AddGroup( GroupName ) function DATABASE:AddGroup( GroupName )
@ -564,6 +589,7 @@ function DATABASE:GetPlayers()
return self.PLAYERS return self.PLAYERS
end end
--- Get the player table from the DATABASE, which contains all UNIT objects. --- Get the player table from the DATABASE, which contains all UNIT objects.
-- The player table contains all UNIT objects of the player with the key the name of the player (PlayerName). -- The player table contains all UNIT objects of the player with the key the name of the player (PlayerName).
-- @param #DATABASE self -- @param #DATABASE self
@ -576,6 +602,7 @@ function DATABASE:GetPlayerUnits()
return self.PLAYERUNITS return self.PLAYERUNITS
end end
--- Get the player table from the DATABASE which have joined in the mission historically. --- Get the player table from the DATABASE which have joined in the mission historically.
-- The player table contains all UNIT objects with the key the name of the player (PlayerName). -- The player table contains all UNIT objects with the key the name of the player (PlayerName).
-- @param #DATABASE self -- @param #DATABASE self
@ -588,6 +615,7 @@ function DATABASE:GetPlayersJoined()
return self.PLAYERSJOINED return self.PLAYERSJOINED
end end
--- Instantiate new Groups within the DCSRTE. --- Instantiate new Groups within the DCSRTE.
-- This method expects EXACTLY the same structure as a structure within the ME, and needs 2 additional fields defined: -- This method expects EXACTLY the same structure as a structure within the ME, and needs 2 additional fields defined:
-- SpawnCountryID, SpawnCategoryID -- SpawnCountryID, SpawnCategoryID
@ -720,8 +748,9 @@ function DATABASE:_RegisterGroupTemplate( GroupTemplate, CoalitionSide, Category
Coalition = self.Templates.Groups[GroupTemplateName].CoalitionID, Coalition = self.Templates.Groups[GroupTemplateName].CoalitionID,
Category = self.Templates.Groups[GroupTemplateName].CategoryID, Category = self.Templates.Groups[GroupTemplateName].CategoryID,
Country = self.Templates.Groups[GroupTemplateName].CountryID, Country = self.Templates.Groups[GroupTemplateName].CountryID,
Units = UnitNames, Units = UnitNames
} ) }
)
end end
--- Get group template. --- Get group template.
@ -768,8 +797,9 @@ function DATABASE:_RegisterStaticTemplate( StaticTemplate, CoalitionID, Category
self:T( { Static = self.Templates.Statics[StaticTemplateName].StaticName, self:T( { Static = self.Templates.Statics[StaticTemplateName].StaticName,
Coalition = self.Templates.Statics[StaticTemplateName].CoalitionID, Coalition = self.Templates.Statics[StaticTemplateName].CoalitionID,
Category = self.Templates.Statics[StaticTemplateName].CategoryID, Category = self.Templates.Statics[StaticTemplateName].CategoryID,
Country = self.Templates.Statics[StaticTemplateName].CountryID, Country = self.Templates.Statics[StaticTemplateName].CountryID
} ) }
)
self:AddStatic( StaticTemplateName ) self:AddStatic( StaticTemplateName )
@ -830,6 +860,20 @@ function DATABASE:GetGroupTemplateFromUnitName( UnitName )
end end
end end
--- Get group template from unit name.
-- @param #DATABASE self
-- @param #string UnitName Name of the unit.
-- @return #table Group template.
function DATABASE:GetUnitTemplateFromUnitName( UnitName )
if self.Templates.Units[UnitName] then
return self.Templates.Units[UnitName]
else
self:E("ERROR: Unit template does not exist for unit "..tostring(UnitName))
return nil
end
end
--- Get coalition ID from client name. --- Get coalition ID from client name.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string ClientName Name of the Client. -- @param #string ClientName Name of the Client.
@ -872,6 +916,8 @@ function DATABASE:GetCategoryFromAirbase( AirbaseName )
return self.AIRBASES[AirbaseName]:GetCategory() return self.AIRBASES[AirbaseName]:GetCategory()
end end
--- Private method that registers all alive players in the mission. --- Private method that registers all alive players in the mission.
-- @param #DATABASE self -- @param #DATABASE self
-- @return #DATABASE self -- @return #DATABASE self
@ -895,7 +941,8 @@ function DATABASE:_RegisterPlayers()
return self return self
end end
--- Private method that registers all Groups and Units within the mission.
--- Private method that registers all Groups and Units within in the mission.
-- @param #DATABASE self -- @param #DATABASE self
-- @return #DATABASE self -- @return #DATABASE self
function DATABASE:_RegisterGroupsAndUnits() function DATABASE:_RegisterGroupsAndUnits()
@ -936,20 +983,21 @@ function DATABASE:_RegisterGroupsAndUnits()
return self return self
end end
--- Private method that registers all Units of skill Client or Player within the mission. --- Private method that registers all Units of skill Client or Player within in the mission.
-- @param #DATABASE self -- @param #DATABASE self
-- @return #DATABASE self -- @return #DATABASE self
function DATABASE:_RegisterClients() function DATABASE:_RegisterClients()
for ClientName, ClientTemplate in pairs( self.Templates.ClientsByName ) do for ClientName, ClientTemplate in pairs( self.Templates.ClientsByName ) do
self:I(string.format("Register Client: %s", tostring(ClientName))) self:I(string.format("Register Client: %s", tostring(ClientName)))
self:AddClient( ClientName ) local client=self:AddClient( ClientName )
client.SpawnCoord=COORDINATE:New(ClientTemplate.x, ClientTemplate.alt, ClientTemplate.y)
end end
return self return self
end end
--- Private method that registers all Statics within the mission. --- Private method that registeres all static objects.
-- @param #DATABASE self -- @param #DATABASE self
function DATABASE:_RegisterStatics() function DATABASE:_RegisterStatics()
@ -992,7 +1040,7 @@ function DATABASE:_RegisterAirbases()
local airbaseUID=airbase:GetID(true) local airbaseUID=airbase:GetID(true)
-- Debug output. -- Debug output.
local text = string.format( "Register %s: %s (ID=%d UID=%d), parking=%d [", AIRBASE.CategoryName[airbase.category], tostring( DCSAirbaseName ), airbaseID, airbaseUID, airbase.NparkingTotal ) local text=string.format("Register %s: %s (UID=%d), Runways=%d, Parking=%d [", AIRBASE.CategoryName[airbase.category], tostring(DCSAirbaseName), airbaseUID, #airbase.runways, airbase.NparkingTotal)
for _,terminalType in pairs(AIRBASE.TerminalType) do for _,terminalType in pairs(AIRBASE.TerminalType) do
if airbase.NparkingTerminal and airbase.NparkingTerminal[terminalType] then if airbase.NparkingTerminal and airbase.NparkingTerminal[terminalType] then
text=text..string.format("%d=%d ", terminalType, airbase.NparkingTerminal[terminalType]) text=text..string.format("%d=%d ", terminalType, airbase.NparkingTerminal[terminalType])
@ -1001,16 +1049,12 @@ function DATABASE:_RegisterAirbases()
text=text.."]" text=text.."]"
self:I(text) self:I(text)
-- Check for DCS bug IDs.
if airbaseID ~= airbase:GetID() then
-- self:E("WARNING: :getID does NOT match :GetID!")
end
end end
return self return self
end end
--- Events --- Events
--- Handles the OnBirth event for the alive units set. --- Handles the OnBirth event for the alive units set.
@ -1090,6 +1134,7 @@ function DATABASE:_EventOnBirth( Event )
end end
--- Handles the OnDead or OnCrash event for alive units set. --- Handles the OnDead or OnCrash event for alive units set.
-- @param #DATABASE self -- @param #DATABASE self
-- @param Core.Event#EVENTDATA Event -- @param Core.Event#EVENTDATA Event
@ -1109,6 +1154,22 @@ function DATABASE:_EventOnDeadOrCrash( Event )
self:DeleteStatic( Event.IniDCSUnitName ) self:DeleteStatic( Event.IniDCSUnitName )
end end
---
-- Maybe a UNIT?
---
-- Delete unit.
if self.UNITS[Event.IniDCSUnitName] then
self:T("STATIC Event for UNIT "..tostring(Event.IniDCSUnitName))
local DCSUnit = _DATABASE:FindUnit( Event.IniDCSUnitName )
self:T({DCSUnit})
if DCSUnit then
--self:I("Creating DEAD Event for UNIT "..tostring(Event.IniDCSUnitName))
--DCSUnit:Destroy(true)
return
end
end
else else
if Event.IniObjectCategory == 1 then if Event.IniObjectCategory == 1 then
@ -1144,6 +1205,7 @@ function DATABASE:_EventOnDeadOrCrash( Event )
self:AccountDestroys( Event ) self:AccountDestroys( Event )
end end
--- Handles the OnPlayerEnterUnit event to fill the active players table (with the unit filter applied). --- Handles the OnPlayerEnterUnit event to fill the active players table (with the unit filter applied).
-- @param #DATABASE self -- @param #DATABASE self
-- @param Core.Event#EVENTDATA Event -- @param Core.Event#EVENTDATA Event
@ -1181,6 +1243,7 @@ function DATABASE:_EventOnPlayerEnterUnit( Event )
end end
end end
--- Handles the OnPlayerLeaveUnit event to clean the active players table. --- Handles the OnPlayerLeaveUnit event to clean the active players table.
-- @param #DATABASE self -- @param #DATABASE self
-- @param Core.Event#EVENTDATA Event -- @param Core.Event#EVENTDATA Event
@ -1266,6 +1329,7 @@ function DATABASE:ForEach( IteratorFunction, FinalizeFunction, arg, Set )
return self return self
end end
--- Iterate the DATABASE and call an iterator function for each **alive** STATIC, providing the STATIC and optional parameters. --- Iterate the DATABASE and call an iterator function for each **alive** STATIC, providing the STATIC and optional parameters.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #function IteratorFunction The function that will be called for each object in the database. The function needs to accept a STATIC parameter. -- @param #function IteratorFunction The function that will be called for each object in the database. The function needs to accept a STATIC parameter.
@ -1278,6 +1342,7 @@ function DATABASE:ForEachStatic( IteratorFunction, FinalizeFunction, ... ) -- R2
return self return self
end end
--- Iterate the DATABASE and call an iterator function for each **alive** UNIT, providing the UNIT and optional parameters. --- Iterate the DATABASE and call an iterator function for each **alive** UNIT, providing the UNIT and optional parameters.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #function IteratorFunction The function that will be called for each object in the database. The function needs to accept a UNIT parameter. -- @param #function IteratorFunction The function that will be called for each object in the database. The function needs to accept a UNIT parameter.
@ -1290,6 +1355,7 @@ function DATABASE:ForEachUnit( IteratorFunction, FinalizeFunction, ... )
return self return self
end end
--- Iterate the DATABASE and call an iterator function for each **alive** GROUP, providing the GROUP and optional parameters. --- Iterate the DATABASE and call an iterator function for each **alive** GROUP, providing the GROUP and optional parameters.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #function IteratorFunction The function that will be called for each object in the database. The function needs to accept a GROUP parameter. -- @param #function IteratorFunction The function that will be called for each object in the database. The function needs to accept a GROUP parameter.
@ -1302,6 +1368,7 @@ function DATABASE:ForEachGroup( IteratorFunction, FinalizeFunction, ... )
return self return self
end end
--- Iterate the DATABASE and call an iterator function for each **ALIVE** player, providing the player name and optional parameters. --- Iterate the DATABASE and call an iterator function for each **ALIVE** player, providing the player name and optional parameters.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #function IteratorFunction The function that will be called for each object in the database. The function needs to accept the player name. -- @param #function IteratorFunction The function that will be called for each object in the database. The function needs to accept the player name.
@ -1314,6 +1381,7 @@ function DATABASE:ForEachPlayer( IteratorFunction, FinalizeFunction, ... )
return self return self
end end
--- Iterate the DATABASE and call an iterator function for each player who has joined the mission, providing the Unit of the player and optional parameters. --- Iterate the DATABASE and call an iterator function for each player who has joined the mission, providing the Unit of the player and optional parameters.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #function IteratorFunction The function that will be called for each object in the database. The function needs to accept a UNIT parameter. -- @param #function IteratorFunction The function that will be called for each object in the database. The function needs to accept a UNIT parameter.
@ -1338,6 +1406,7 @@ function DATABASE:ForEachPlayerUnit( IteratorFunction, FinalizeFunction, ... )
return self return self
end end
--- Iterate the DATABASE and call an iterator function for each CLIENT, providing the CLIENT to the function and optional parameters. --- Iterate the DATABASE and call an iterator function for each CLIENT, providing the CLIENT to the function and optional parameters.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #function IteratorFunction The function that will be called object in the database. The function needs to accept a CLIENT parameter. -- @param #function IteratorFunction The function that will be called object in the database. The function needs to accept a CLIENT parameter.
@ -1362,6 +1431,7 @@ function DATABASE:ForEachCargo( IteratorFunction, ... )
return self return self
end end
--- Handles the OnEventNewCargo event. --- Handles the OnEventNewCargo event.
-- @param #DATABASE self -- @param #DATABASE self
-- @param Core.Event#EVENTDATA EventData -- @param Core.Event#EVENTDATA EventData
@ -1373,6 +1443,7 @@ function DATABASE:OnEventNewCargo( EventData )
end end
end end
--- Handles the OnEventDeleteCargo. --- Handles the OnEventDeleteCargo.
-- @param #DATABASE self -- @param #DATABASE self
-- @param Core.Event#EVENTDATA EventData -- @param Core.Event#EVENTDATA EventData
@ -1384,6 +1455,7 @@ function DATABASE:OnEventDeleteCargo( EventData )
end end
end end
--- Handles the OnEventNewZone event. --- Handles the OnEventNewZone event.
-- @param #DATABASE self -- @param #DATABASE self
-- @param Core.Event#EVENTDATA EventData -- @param Core.Event#EVENTDATA EventData
@ -1395,6 +1467,7 @@ function DATABASE:OnEventNewZone( EventData )
end end
end end
--- Handles the OnEventDeleteZone. --- Handles the OnEventDeleteZone.
-- @param #DATABASE self -- @param #DATABASE self
-- @param Core.Event#EVENTDATA EventData -- @param Core.Event#EVENTDATA EventData
@ -1406,6 +1479,8 @@ function DATABASE:OnEventDeleteZone( EventData )
end end
end end
--- Gets the player settings --- Gets the player settings
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string PlayerName -- @param #string PlayerName
@ -1415,6 +1490,7 @@ function DATABASE:GetPlayerSettings( PlayerName )
return self.PLAYERSETTINGS[PlayerName] return self.PLAYERSETTINGS[PlayerName]
end end
--- Sets the player settings --- Sets the player settings
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string PlayerName -- @param #string PlayerName
@ -1425,19 +1501,19 @@ function DATABASE:SetPlayerSettings( PlayerName, Settings )
self.PLAYERSETTINGS[PlayerName] = Settings self.PLAYERSETTINGS[PlayerName] = Settings
end end
--- Add a flight group to the data base. --- Add an OPS group (FLIGHTGROUP, ARMYGROUP, NAVYGROUP) to the data base.
-- @param #DATABASE self -- @param #DATABASE self
-- @param Ops.FlightGroup#FLIGHTGROUP flightgroup -- @param Ops.OpsGroup#OPSGROUP opsgroup The OPS group added to the DB.
function DATABASE:AddFlightGroup( flightgroup ) function DATABASE:AddOpsGroup(opsgroup)
self:I( { NewFlightGroup = flightgroup.groupname } ) --env.info("Adding OPSGROUP "..tostring(opsgroup.groupname))
self.FLIGHTGROUPS[flightgroup.groupname] = flightgroup self.FLIGHTGROUPS[opsgroup.groupname]=opsgroup
end end
--- Get a flight group from the data base. --- Get an OPS group (FLIGHTGROUP, ARMYGROUP, NAVYGROUP) from the data base.
-- @param #DATABASE self -- @param #DATABASE self
-- @param #string groupname Group name of the flight group. Can also be passed as GROUP object. -- @param #string groupname Group name of the group. Can also be passed as GROUP object.
-- @return Ops.FlightGroup#FLIGHTGROUP Flight group object. -- @return Ops.OpsGroup#OPSGROUP OPS group object.
function DATABASE:GetFlightGroup( groupname ) function DATABASE:GetOpsGroup(groupname)
-- Get group and group name. -- Get group and group name.
if type(groupname)=="string" then if type(groupname)=="string" then
@ -1445,9 +1521,53 @@ function DATABASE:GetFlightGroup( groupname )
groupname=groupname:GetName() groupname=groupname:GetName()
end end
--env.info("Getting OPSGROUP "..tostring(groupname))
return self.FLIGHTGROUPS[groupname] return self.FLIGHTGROUPS[groupname]
end end
--- Find an OPSGROUP (FLIGHTGROUP, ARMYGROUP, NAVYGROUP) in the data base.
-- @param #DATABASE self
-- @param #string groupname Group name of the group. Can also be passed as GROUP object.
-- @return Ops.OpsGroup#OPSGROUP OPS group object.
function DATABASE:FindOpsGroup(groupname)
-- Get group and group name.
if type(groupname)=="string" then
else
groupname=groupname:GetName()
end
--env.info("Getting OPSGROUP "..tostring(groupname))
return self.FLIGHTGROUPS[groupname]
end
--- Find an OPSGROUP (FLIGHTGROUP, ARMYGROUP, NAVYGROUP) in the data base for a given unit.
-- @param #DATABASE self
-- @param #string unitname Unit name. Can also be passed as UNIT object.
-- @return Ops.OpsGroup#OPSGROUP OPS group object.
function DATABASE:FindOpsGroupFromUnit(unitname)
local unit=nil --Wrapper.Unit#UNIT
local groupname
-- Get group and group name.
if type(unitname)=="string" then
unit=UNIT:FindByName(unitname)
else
unit=unitname
end
if unit then
groupname=unit:GetGroup():GetName()
end
if groupname then
return self.FLIGHTGROUPS[groupname]
else
return nil
end
end
--- Add a flight control to the data base. --- Add a flight control to the data base.
-- @param #DATABASE self -- @param #DATABASE self
-- @param Ops.FlightControl#FLIGHTCONTROL flightcontrol -- @param Ops.FlightControl#FLIGHTCONTROL flightcontrol

View File

@ -405,7 +405,7 @@ do -- FSM
Transition.To = To Transition.To = To
-- Debug message. -- Debug message.
self:T2( Transition ) --self:T3( Transition )
self._Transitions[Transition] = Transition self._Transitions[Transition] = Transition
self:_eventmap( self.Events, Transition ) self:_eventmap( self.Events, Transition )
@ -426,7 +426,7 @@ do -- FSM
-- @param #table ReturnEvents A table indicating for which returned events of the SubFSM which Event must be triggered in the FSM. -- @param #table ReturnEvents A table indicating for which returned events of the SubFSM which Event must be triggered in the FSM.
-- @return Core.Fsm#FSM_PROCESS The SubFSM. -- @return Core.Fsm#FSM_PROCESS The SubFSM.
function FSM:AddProcess( From, Event, Process, ReturnEvents ) function FSM:AddProcess( From, Event, Process, ReturnEvents )
self:T( { From, Event } ) --self:T3( { From, Event } )
local Sub = {} local Sub = {}
Sub.From = From Sub.From = From
@ -525,7 +525,7 @@ do -- FSM
Process._Scores[State].ScoreText = ScoreText Process._Scores[State].ScoreText = ScoreText
Process._Scores[State].Score = Score Process._Scores[State].Score = Score
self:T( Process._Scores ) --self:T3( Process._Scores )
return Process return Process
end end
@ -568,7 +568,7 @@ do -- FSM
self[__Event] = self[__Event] or self:_delayed_transition(Event) self[__Event] = self[__Event] or self:_delayed_transition(Event)
-- Debug message. -- Debug message.
self:T2( "Added methods: " .. Event .. ", " .. __Event ) --self:T3( "Added methods: " .. Event .. ", " .. __Event )
Events[Event] = self.Events[Event] or { map = {} } Events[Event] = self.Events[Event] or { map = {} }
self:_add_to_map( Events[Event].map, EventStructure ) self:_add_to_map( Events[Event].map, EventStructure )
@ -784,7 +784,7 @@ do -- FSM
return function( self, DelaySeconds, ... ) return function( self, DelaySeconds, ... )
-- Debug. -- Debug.
self:T2( "Delayed Event: " .. EventName ) self:T3( "Delayed Event: " .. EventName )
local CallID = 0 local CallID = 0
if DelaySeconds ~= nil then if DelaySeconds ~= nil then
@ -802,23 +802,23 @@ do -- FSM
self._EventSchedules[EventName] = CallID self._EventSchedules[EventName] = CallID
-- Debug output. -- Debug output.
self:T2( string.format( "NEGATIVE Event %s delayed by %.1f sec SCHEDULED with CallID=%s", EventName, DelaySeconds, tostring( CallID ) ) ) self:T2(string.format("NEGATIVE Event %s delayed by %.3f sec SCHEDULED with CallID=%s", EventName, DelaySeconds, tostring(CallID)))
else else
self:T2( string.format( "NEGATIVE Event %s delayed by %.1f sec CANCELLED as we already have such an event in the queue.", EventName, DelaySeconds ) ) self:T2(string.format("NEGATIVE Event %s delayed by %.3f sec CANCELLED as we already have such an event in the queue.", EventName, DelaySeconds))
-- reschedule -- reschedule
end end
else else
CallID = self.CallScheduler:Schedule( self, self._handler, { EventName, ... }, DelaySeconds or 1, nil, nil, nil, 4, true ) CallID = self.CallScheduler:Schedule( self, self._handler, { EventName, ... }, DelaySeconds or 1, nil, nil, nil, 4, true )
self:T2( string.format( "Event %s delayed by %.1f sec SCHEDULED with CallID=%s", EventName, DelaySeconds, tostring( CallID ) ) ) self:T2(string.format("Event %s delayed by %.3f sec SCHEDULED with CallID=%s", EventName, DelaySeconds, tostring(CallID)))
end end
else else
error( "FSM: An asynchronous event trigger requires a DelaySeconds parameter!!! This can be positive or negative! Sorry, but will not process this." ) error( "FSM: An asynchronous event trigger requires a DelaySeconds parameter!!! This can be positive or negative! Sorry, but will not process this." )
end end
-- Debug. -- Debug.
self:T2( { CallID = CallID } ) --self:T3( { CallID = CallID } )
end end
end end
@ -841,7 +841,7 @@ do -- FSM
function FSM:_gosub( ParentFrom, ParentEvent ) function FSM:_gosub( ParentFrom, ParentEvent )
local fsmtable = {} local fsmtable = {}
if self.subs[ParentFrom] and self.subs[ParentFrom][ParentEvent] then if self.subs[ParentFrom] and self.subs[ParentFrom][ParentEvent] then
self:T( { ParentFrom, ParentEvent, self.subs[ParentFrom], self.subs[ParentFrom][ParentEvent] } ) --self:T3( { ParentFrom, ParentEvent, self.subs[ParentFrom], self.subs[ParentFrom][ParentEvent] } )
return self.subs[ParentFrom][ParentEvent] return self.subs[ParentFrom][ParentEvent]
else else
return {} return {}
@ -888,7 +888,7 @@ do -- FSM
end end
end end
self:T3( { Map, Event } ) --self:T3( { Map, Event } )
end end
--- Get current state. --- Get current state.
@ -908,7 +908,7 @@ do -- FSM
--- Check if FSM is in state. --- Check if FSM is in state.
-- @param #FSM self -- @param #FSM self
-- @param #string State State name. -- @param #string State State name.
-- @param #boolean If true, FSM is in this state. -- @return #boolean If true, FSM is in this state.
function FSM:Is( State ) function FSM:Is( State )
return self.current == State return self.current == State
end end
@ -916,7 +916,7 @@ do -- FSM
--- Check if FSM is in state. --- Check if FSM is in state.
-- @param #FSM self -- @param #FSM self
-- @param #string State State name. -- @param #string State State name.
-- @param #boolean If true, FSM is in this state. -- @return #boolean If true, FSM is in this state.
function FSM:is(state) function FSM:is(state)
return self.current == state return self.current == state
end end
@ -1146,7 +1146,7 @@ do -- FSM_PROCESS
-- @param #FSM_PROCESS self -- @param #FSM_PROCESS self
-- @return #FSM_PROCESS -- @return #FSM_PROCESS
function FSM_PROCESS:Copy( Controllable, Task ) function FSM_PROCESS:Copy( Controllable, Task )
self:T( { self:GetClassNameAndID() } ) --self:T3( { self:GetClassNameAndID() } )
local NewFsm = self:New( Controllable, Task ) -- Core.Fsm#FSM_PROCESS local NewFsm = self:New( Controllable, Task ) -- Core.Fsm#FSM_PROCESS
@ -1171,13 +1171,13 @@ do -- FSM_PROCESS
-- Copy End States -- Copy End States
for EndStateID, EndState in pairs( self:GetEndStates() ) do for EndStateID, EndState in pairs( self:GetEndStates() ) do
self:T( EndState ) --self:T3( EndState )
NewFsm:AddEndState( EndState ) NewFsm:AddEndState( EndState )
end end
-- Copy the score tables -- Copy the score tables
for ScoreID, Score in pairs( self:GetScores() ) do for ScoreID, Score in pairs( self:GetScores() ) do
self:T( Score ) --self:T3( Score )
NewFsm:AddScore( ScoreID, Score.ScoreText, Score.Score ) NewFsm:AddScore( ScoreID, Score.ScoreText, Score.Score )
end end
@ -1422,7 +1422,7 @@ do -- FSM_SET
-- @param #FSM_SET self -- @param #FSM_SET self
-- @return Core.Set#SET_BASE -- @return Core.Set#SET_BASE
function FSM_SET:Get() function FSM_SET:Get()
return self.Controllable return self.Set
end end
function FSM_SET:_call_handler( step, trigger, params, EventName ) function FSM_SET:_call_handler( step, trigger, params, EventName )

View File

@ -11,6 +11,7 @@
-- ### Author: **Applevangelist** -- ### Author: **Applevangelist**
-- --
-- Date: 5 May 2021 -- Date: 5 May 2021
-- Last Update: Sep 2022
-- --
-- === -- ===
--- ---
@ -27,6 +28,7 @@
-- @field #string Tag Tag to identify commands. -- @field #string Tag Tag to identify commands.
-- @field #table Keywords Table of keywords to recognize. -- @field #table Keywords Table of keywords to recognize.
-- @field #string version Version of #MARKEROPS_BASE. -- @field #string version Version of #MARKEROPS_BASE.
-- @field #boolean Casesensitive Enforce case when identifying the Tag, i.e. tag ~= Tag
-- @extends Core.Fsm#FSM -- @extends Core.Fsm#FSM
--- *Fiat lux.* -- Latin proverb. --- *Fiat lux.* -- Latin proverb.
@ -42,16 +44,18 @@ MARKEROPS_BASE = {
ClassName = "MARKEROPS", ClassName = "MARKEROPS",
Tag = "mytag", Tag = "mytag",
Keywords = {}, Keywords = {},
version = "0.0.1", version = "0.1.0",
debug = false, debug = false,
Casesensitive = true,
} }
--- Function to instantiate a new #MARKEROPS_BASE object. --- Function to instantiate a new #MARKEROPS_BASE object.
-- @param #MARKEROPS_BASE self -- @param #MARKEROPS_BASE self
-- @param #string Tagname Name to identify us from the event text. -- @param #string Tagname Name to identify us from the event text.
-- @param #table Keywords Table of keywords recognized from the event text. -- @param #table Keywords Table of keywords recognized from the event text.
-- @param #boolean Casesensitive (Optional) Switch case sensitive identification of Tagname. Defaults to true.
-- @return #MARKEROPS_BASE self -- @return #MARKEROPS_BASE self
function MARKEROPS_BASE:New(Tagname,Keywords) function MARKEROPS_BASE:New(Tagname,Keywords,Casesensitive)
-- Inherit FSM -- Inherit FSM
local self=BASE:Inherit(self, FSM:New()) -- #MARKEROPS_BASE local self=BASE:Inherit(self, FSM:New()) -- #MARKEROPS_BASE
@ -61,6 +65,11 @@ function MARKEROPS_BASE:New(Tagname,Keywords)
self.Tag = Tagname or "mytag"-- #string self.Tag = Tagname or "mytag"-- #string
self.Keywords = Keywords or {} -- #table - might want to use lua regex here, too self.Keywords = Keywords or {} -- #table - might want to use lua regex here, too
self.debug = false self.debug = false
self.Casesensitive = true
if Casesensitive and Casesensitive == false then
self.Casesensitive = false
end
----------------------- -----------------------
--- FSM Transitions --- --- FSM Transitions ---
@ -178,10 +187,17 @@ end
-- @return #boolean -- @return #boolean
function MARKEROPS_BASE:_MatchTag(Eventtext) function MARKEROPS_BASE:_MatchTag(Eventtext)
local matches = false local matches = false
if not self.Casesensitive then
local type = string.lower(self.Tag) -- #string local type = string.lower(self.Tag) -- #string
if string.find(string.lower(Eventtext),type) then if string.find(string.lower(Eventtext),type) then
matches = true --event text contains tag matches = true --event text contains tag
end end
else
local type = self.Tag -- #string
if string.find(Eventtext,type) then
matches = true --event text contains tag
end
end
return matches return matches
end end

View File

@ -239,6 +239,7 @@ do -- MENU_BASE
function MENU_BASE:GetMenu( MenuText ) function MENU_BASE:GetMenu( MenuText )
return self.Menus[MenuText] return self.Menus[MenuText]
end end
--- Sets a menu stamp for later prevention of menu removal. --- Sets a menu stamp for later prevention of menu removal.
-- @param #MENU_BASE self -- @param #MENU_BASE self
-- @param MenuStamp -- @param MenuStamp
@ -376,6 +377,7 @@ do -- MENU_MISSION
end end
end end
--- Refreshes a radio item for a mission --- Refreshes a radio item for a mission
-- @param #MENU_MISSION self -- @param #MENU_MISSION self
-- @return #MENU_MISSION -- @return #MENU_MISSION
@ -813,6 +815,7 @@ do
end end
end end
--- Refreshes a new radio item for a group and submenus --- Refreshes a new radio item for a group and submenus
-- @param #MENU_GROUP self -- @param #MENU_GROUP self
-- @return #MENU_GROUP -- @return #MENU_GROUP
@ -829,6 +832,29 @@ do
return self return self
end end
--- Refreshes a new radio item for a group and submenus, ordering by (numerical) MenuTag
-- @param #MENU_GROUP self
-- @return #MENU_GROUP
function MENU_GROUP:RefreshAndOrderByTag()
do
missionCommands.removeItemForGroup( self.GroupID, self.MenuPath )
missionCommands.addSubMenuForGroup( self.GroupID, self.MenuText, self.MenuParentPath )
local MenuTable = {}
for MenuText, Menu in pairs( self.Menus or {} ) do
local tag = Menu.MenuTag or math.random(1,10000)
MenuTable[#MenuTable+1] = {Tag=tag, Enty=Menu}
end
table.sort(MenuTable, function (k1, k2) return k1.tag < k2.tag end )
for _, Menu in pairs( MenuTable ) do
Menu.Entry:Refresh()
end
end
return self
end
--- Removes the sub menus recursively of this MENU_GROUP. --- Removes the sub menus recursively of this MENU_GROUP.
-- @param #MENU_GROUP self -- @param #MENU_GROUP self
-- @param MenuStamp -- @param MenuStamp
@ -1180,4 +1206,3 @@ do
return self return self
end end
end end

View File

@ -12,7 +12,6 @@
-- * Send messages to a specific group. -- * Send messages to a specific group.
-- * Send messages to a specific unit or client. -- * Send messages to a specific unit or client.
-- --
--
-- === -- ===
-- --
-- @module Core.Message -- @module Core.Message
@ -263,6 +262,30 @@ function MESSAGE:ToUnit( Unit, Settings )
return self return self
end end
--- Sends a MESSAGE to a Unit.
-- @param #MESSAGE self
-- @param Wrapper.Unit#UNIT Unit to which the message is displayed.
-- @return #MESSAGE Message object.
function MESSAGE:ToUnit( Unit, Settings )
self:F( Unit.IdentifiableName )
if Unit then
if self.MessageType then
local Settings = Settings or ( Unit and _DATABASE:GetPlayerSettings( Unit:GetPlayerName() ) ) or _SETTINGS -- Core.Settings#SETTINGS
self.MessageDuration = Settings:GetMessageTime( self.MessageType )
self.MessageCategory = "" -- self.MessageType .. ": "
end
if self.MessageDuration ~= 0 then
self:T( self.MessageCategory .. self.MessageText:gsub("\n$",""):gsub("\n$","") .. " / " .. self.MessageDuration )
trigger.action.outTextForUnit( Unit:GetID(), self.MessageCategory .. self.MessageText:gsub("\n$",""):gsub("\n$",""), self.MessageDuration, self.ClearScreen )
end
end
return self
end
--- Sends a MESSAGE to the Blue coalition. --- Sends a MESSAGE to the Blue coalition.
-- @param #MESSAGE self -- @param #MESSAGE self
-- @return #MESSAGE -- @return #MESSAGE

View File

@ -825,7 +825,11 @@ do -- COORDINATE
-- @param #COORDINATE TargetCoordinate The target COORDINATE. -- @param #COORDINATE TargetCoordinate The target COORDINATE.
-- @return DCS#Vec3 DirectionVec3 The direction vector in Vec3 format. -- @return DCS#Vec3 DirectionVec3 The direction vector in Vec3 format.
function COORDINATE:GetDirectionVec3( TargetCoordinate ) function COORDINATE:GetDirectionVec3( TargetCoordinate )
if TargetCoordinate then
return { x = TargetCoordinate.x - self.x, y = TargetCoordinate.y - self.y, z = TargetCoordinate.z - self.z } return { x = TargetCoordinate.x - self.x, y = TargetCoordinate.y - self.y, z = TargetCoordinate.z - self.z }
else
return { x=0,y=0,z=0}
end
end end
@ -875,6 +879,11 @@ do -- COORDINATE
-- Get the vector from A to B -- Get the vector from A to B
local vec=UTILS.VecSubstract(ToCoordinate, self) local vec=UTILS.VecSubstract(ToCoordinate, self)
if f>1 then
local norm=UTILS.VecNorm(vec)
f=Fraction/norm
end
-- Scale the vector. -- Scale the vector.
vec.x=f*vec.x vec.x=f*vec.x
vec.y=f*vec.y vec.y=f*vec.y
@ -883,7 +892,9 @@ do -- COORDINATE
-- Move the vector to start at the end of A. -- Move the vector to start at the end of A.
vec=UTILS.VecAdd(self, vec) vec=UTILS.VecAdd(self, vec)
-- Create a new coordiante object.
local coord=COORDINATE:New(vec.x,vec.y,vec.z) local coord=COORDINATE:New(vec.x,vec.y,vec.z)
return coord return coord
end end
@ -2267,7 +2278,7 @@ do -- COORDINATE
end end
--- Creates a free form shape on the F10 map. The first point is the current COORDINATE. The remaining points need to be specified. --- Creates a free form shape on the F10 map. The first point is the current COORDINATE. The remaining points need to be specified.
-- **NOTE**: A free form polygon must have **at least three points** in total and currently only **up to 10 points** in total are supported. -- **NOTE**: A free form polygon must have **at least three points** in total and currently only **up to 15 points** in total are supported.
-- @param #COORDINATE self -- @param #COORDINATE self
-- @param #table Coordinates Table of coordinates of the remaining points of the shape. -- @param #table Coordinates Table of coordinates of the remaining points of the shape.
-- @param #number Coalition Coalition: All=-1, Neutral=0, Red=1, Blue=2. Default -1=All. -- @param #number Coalition Coalition: All=-1, Neutral=0, Red=1, Blue=2. Default -1=All.
@ -2320,8 +2331,28 @@ do -- COORDINATE
trigger.action.markupToAll(7, Coalition, MarkID, vecs[1], vecs[2], vecs[3], vecs[4], vecs[5], vecs[6], vecs[7], vecs[8], vecs[9], Color, FillColor, LineType, ReadOnly, Text or "") trigger.action.markupToAll(7, Coalition, MarkID, vecs[1], vecs[2], vecs[3], vecs[4], vecs[5], vecs[6], vecs[7], vecs[8], vecs[9], Color, FillColor, LineType, ReadOnly, Text or "")
elseif #vecs==10 then elseif #vecs==10 then
trigger.action.markupToAll(7, Coalition, MarkID, vecs[1], vecs[2], vecs[3], vecs[4], vecs[5], vecs[6], vecs[7], vecs[8], vecs[9], vecs[10], Color, FillColor, LineType, ReadOnly, Text or "") trigger.action.markupToAll(7, Coalition, MarkID, vecs[1], vecs[2], vecs[3], vecs[4], vecs[5], vecs[6], vecs[7], vecs[8], vecs[9], vecs[10], Color, FillColor, LineType, ReadOnly, Text or "")
elseif #vecs==11 then
trigger.action.markupToAll(7, Coalition, MarkID, vecs[1], vecs[2], vecs[3], vecs[4], vecs[5], vecs[6], vecs[7], vecs[8], vecs[9], vecs[10],
vecs[11],
Color, FillColor, LineType, ReadOnly, Text or "")
elseif #vecs==12 then
trigger.action.markupToAll(7, Coalition, MarkID, vecs[1], vecs[2], vecs[3], vecs[4], vecs[5], vecs[6], vecs[7], vecs[8], vecs[9], vecs[10],
vecs[11], vecs[12],
Color, FillColor, LineType, ReadOnly, Text or "")
elseif #vecs==13 then
trigger.action.markupToAll(7, Coalition, MarkID, vecs[1], vecs[2], vecs[3], vecs[4], vecs[5], vecs[6], vecs[7], vecs[8], vecs[9], vecs[10],
vecs[11], vecs[12], vecs[13],
Color, FillColor, LineType, ReadOnly, Text or "")
elseif #vecs==14 then
trigger.action.markupToAll(7, Coalition, MarkID, vecs[1], vecs[2], vecs[3], vecs[4], vecs[5], vecs[6], vecs[7], vecs[8], vecs[9], vecs[10],
vecs[11], vecs[12], vecs[13], vecs[14],
Color, FillColor, LineType, ReadOnly, Text or "")
elseif #vecs==15 then
trigger.action.markupToAll(7, Coalition, MarkID, vecs[1], vecs[2], vecs[3], vecs[4], vecs[5], vecs[6], vecs[7], vecs[8], vecs[9], vecs[10],
vecs[11], vecs[12], vecs[13], vecs[14], vecs[15],
Color, FillColor, LineType, ReadOnly, Text or "")
else else
self:E("ERROR: Currently a free form polygon can only have 10 points in total!") self:E("ERROR: Currently a free form polygon can only have 15 points in total!")
-- Unfortunately, unpack(vecs) does not work! So no idea how to generalize this :( -- Unfortunately, unpack(vecs) does not work! So no idea how to generalize this :(
trigger.action.markupToAll(7, Coalition, MarkID, unpack(vecs), Color, FillColor, LineType, ReadOnly, Text or "") trigger.action.markupToAll(7, Coalition, MarkID, unpack(vecs), Color, FillColor, LineType, ReadOnly, Text or "")
end end
@ -2751,7 +2782,7 @@ do -- COORDINATE
return "BR, " .. self:GetBRText( AngleRadians, Distance, Settings ) return "BR, " .. self:GetBRText( AngleRadians, Distance, Settings )
end end
--- Return a BRAA string from a COORDINATE to the COORDINATE. --- Return a BRA string from a COORDINATE to the COORDINATE.
-- @param #COORDINATE self -- @param #COORDINATE self
-- @param #COORDINATE FromCoordinate The coordinate to measure the distance and the bearing from. -- @param #COORDINATE FromCoordinate The coordinate to measure the distance and the bearing from.
-- @param Core.Settings#SETTINGS Settings (optional) The settings. Can be nil, and in this case the default settings are used. If you want to specify your own settings, use the _SETTINGS object. -- @param Core.Settings#SETTINGS Settings (optional) The settings. Can be nil, and in this case the default settings are used. If you want to specify your own settings, use the _SETTINGS object.

View File

@ -109,9 +109,11 @@ function SCHEDULEDISPATCHER:AddSchedule( Scheduler, ScheduleFunction, ScheduleAr
self.ObjectSchedulers = self.ObjectSchedulers or setmetatable( {}, { __mode = "v" } ) self.ObjectSchedulers = self.ObjectSchedulers or setmetatable( {}, { __mode = "v" } )
if Scheduler.MasterObject then if Scheduler.MasterObject then
--env.info("FF Object Scheduler")
self.ObjectSchedulers[CallID] = Scheduler self.ObjectSchedulers[CallID] = Scheduler
self:F3( { CallID = CallID, ObjectScheduler = tostring( self.ObjectSchedulers[CallID] ), MasterObject = tostring( Scheduler.MasterObject ) } ) self:F3( { CallID = CallID, ObjectScheduler = tostring( self.ObjectSchedulers[CallID] ), MasterObject = tostring( Scheduler.MasterObject ) } )
else else
--env.info("FF Persistent Scheduler")
self.PersistentSchedulers[CallID] = Scheduler self.PersistentSchedulers[CallID] = Scheduler
self:F3( { CallID = CallID, PersistentScheduler = self.PersistentSchedulers[CallID] } ) self:F3( { CallID = CallID, PersistentScheduler = self.PersistentSchedulers[CallID] } )
end end
@ -122,7 +124,7 @@ function SCHEDULEDISPATCHER:AddSchedule( Scheduler, ScheduleFunction, ScheduleAr
self.Schedule[Scheduler][CallID].Function = ScheduleFunction self.Schedule[Scheduler][CallID].Function = ScheduleFunction
self.Schedule[Scheduler][CallID].Arguments = ScheduleArguments self.Schedule[Scheduler][CallID].Arguments = ScheduleArguments
self.Schedule[Scheduler][CallID].StartTime = timer.getTime() + ( Start or 0 ) self.Schedule[Scheduler][CallID].StartTime = timer.getTime() + ( Start or 0 )
self.Schedule[Scheduler][CallID].Start = Start + 0.1 self.Schedule[Scheduler][CallID].Start = Start + 0.001
self.Schedule[Scheduler][CallID].Repeat = Repeat or 0 self.Schedule[Scheduler][CallID].Repeat = Repeat or 0
self.Schedule[Scheduler][CallID].Randomize = Randomize or 0 self.Schedule[Scheduler][CallID].Randomize = Randomize or 0
self.Schedule[Scheduler][CallID].Stop = Stop self.Schedule[Scheduler][CallID].Stop = Stop
@ -217,6 +219,7 @@ function SCHEDULEDISPATCHER:AddSchedule( Scheduler, ScheduleFunction, ScheduleAr
if ShowTrace then if ShowTrace then
SchedulerObject:T( Prefix .. Name .. ":" .. Line .. " (" .. Source .. ")" ) SchedulerObject:T( Prefix .. Name .. ":" .. Line .. " (" .. Source .. ")" )
end end
-- The master object is passed as first parameter. A few :Schedule() calls in MOOSE expect this currently. But in principle it should be removed.
return ScheduleFunction( SchedulerObject, unpack( ScheduleArguments ) ) return ScheduleFunction( SchedulerObject, unpack( ScheduleArguments ) )
end end
Status, Result = xpcall( Timer, ErrorHandler ) Status, Result = xpcall( Timer, ErrorHandler )
@ -314,7 +317,7 @@ end
--- Stop dispatcher. --- Stop dispatcher.
-- @param #SCHEDULEDISPATCHER self -- @param #SCHEDULEDISPATCHER self
-- @param Core.Scheduler#SCHEDULER Scheduler Scheduler object. -- @param Core.Scheduler#SCHEDULER Scheduler Scheduler object.
-- @param #table CallID Call ID. -- @param #string CallID (Optional) Scheduler Call ID. If nil, all pending schedules are stopped recursively.
function SCHEDULEDISPATCHER:Stop( Scheduler, CallID ) function SCHEDULEDISPATCHER:Stop( Scheduler, CallID )
self:F2( { Stop = CallID, Scheduler = Scheduler } ) self:F2( { Stop = CallID, Scheduler = Scheduler } )

View File

@ -237,7 +237,7 @@ end
-- @param #number Stop Time interval in seconds after which the scheduler will be stopped. -- @param #number Stop Time interval in seconds after which the scheduler will be stopped.
-- @param #number TraceLevel Trace level [0,3]. Default 3. -- @param #number TraceLevel Trace level [0,3]. Default 3.
-- @param Core.Fsm#FSM Fsm Finite state model. -- @param Core.Fsm#FSM Fsm Finite state model.
-- @return #table The ScheduleID of the planned schedule. -- @return #string The Schedule ID of the planned schedule.
function SCHEDULER:Schedule( MasterObject, SchedulerFunction, SchedulerArguments, Start, Repeat, RandomizeFactor, Stop, TraceLevel, Fsm ) function SCHEDULER:Schedule( MasterObject, SchedulerFunction, SchedulerArguments, Start, Repeat, RandomizeFactor, Stop, TraceLevel, Fsm )
self:F2( { Start, Repeat, RandomizeFactor, Stop } ) self:F2( { Start, Repeat, RandomizeFactor, Stop } )
self:T3( { SchedulerArguments } ) self:T3( { SchedulerArguments } )

View File

@ -201,9 +201,7 @@ do -- SET_BASE
self:F2( { ObjectName = ObjectName } ) self:F2( { ObjectName = ObjectName } )
local TriggerEvent = true local TriggerEvent = true
if NoTriggerEvent then if NoTriggerEvent then TriggerEvent = false end
TriggerEvent = false
end
local Object = self.Set[ObjectName] local Object = self.Set[ObjectName]
@ -286,6 +284,7 @@ do -- SET_BASE
return self return self
end end
--- Get the *union* of two sets. --- Get the *union* of two sets.
-- @param #SET_BASE self -- @param #SET_BASE self
-- @param Core.Set#SET_BASE SetB Set *B*. -- @param Core.Set#SET_BASE SetB Set *B*.
@ -309,6 +308,7 @@ do -- SET_BASE
-- @param #SET_BASE self -- @param #SET_BASE self
-- @param Core.Set#SET_BASE SetB Set other set, called *B*. -- @param Core.Set#SET_BASE SetB Set other set, called *B*.
-- @return Core.Set#SET_BASE A set of objects that is included in set *A* **and** in set *B*. -- @return Core.Set#SET_BASE A set of objects that is included in set *A* **and** in set *B*.
function SET_BASE:GetSetIntersection(SetB) function SET_BASE:GetSetIntersection(SetB)
local intersection=SET_BASE:New() local intersection=SET_BASE:New()
@ -765,6 +765,7 @@ do -- SET_BASE
return self return self
end end
----- Iterate the SET_BASE and call an iterator function for each **alive** unit, providing the Unit and optional parameters. ----- Iterate the SET_BASE and call an iterator function for each **alive** unit, providing the Unit and optional parameters.
---- @param #SET_BASE self ---- @param #SET_BASE self
---- @param #function IteratorFunction The function that will be called when there is an alive unit in the SET_BASE. The function needs to accept a UNIT parameter. ---- @param #function IteratorFunction The function that will be called when there is an alive unit in the SET_BASE. The function needs to accept a UNIT parameter.
@ -1060,8 +1061,9 @@ do -- SET_GROUP
-- Note that for each unit in the group that is set, a default cargo bay limit is initialized. -- Note that for each unit in the group that is set, a default cargo bay limit is initialized.
-- @param Core.Set#SET_GROUP self -- @param Core.Set#SET_GROUP self
-- @param Wrapper.Group#GROUP group The group which should be added to the set. -- @param Wrapper.Group#GROUP group The group which should be added to the set.
-- @param #boolean DontSetCargoBayLimit If true, do not attempt to auto-add the cargo bay limit per unit in this group.
-- @return Core.Set#SET_GROUP self -- @return Core.Set#SET_GROUP self
function SET_GROUP:AddGroup( group ) function SET_GROUP:AddGroup( group, DontSetCargoBayLimit )
self:Add( group:GetName(), group ) self:Add( group:GetName(), group )
@ -1170,6 +1172,30 @@ do -- SET_GROUP
return self return self
end end
--- Builds a set of groups in zones.
-- @param #SET_GROUP self
-- @param #table Zones Table of Core.Zone#ZONE Zone objects, or a Core.Set#SET_ZONE
-- @return #SET_GROUP self
function SET_GROUP:FilterZones( Zones )
if not self.Filter.Zones then
self.Filter.Zones = {}
end
local zones = {}
if Zones.ClassName and Zones.ClassName == "SET_ZONE" then
zones = Zones.Set
elseif type( Zones ) ~= "table" or (type( Zones ) == "table" and Zones.ClassName ) then
self:E("***** FilterZones needs either a table of ZONE Objects or a SET_ZONE as parameter!")
return self
else
zones = Zones
end
for _,Zone in pairs( zones ) do
local zonename = Zone:GetName()
self.Filter.Zones[zonename] = Zone
end
return self
end
--- Builds a set of groups of coalitions. --- Builds a set of groups of coalitions.
-- Possible current coalitions are red, blue and neutral. -- Possible current coalitions are red, blue and neutral.
-- @param #SET_GROUP self -- @param #SET_GROUP self
@ -1439,6 +1465,7 @@ do -- SET_GROUP
return self return self
end end
--- Iterate the SET_GROUP and call an iterator function for each **alive** GROUP presence completely in a @{Zone}, providing the GROUP and optional parameters to the called function. --- Iterate the SET_GROUP and call an iterator function for each **alive** GROUP presence completely in a @{Zone}, providing the GROUP and optional parameters to the called function.
-- @param #SET_GROUP self -- @param #SET_GROUP self
-- @param Core.Zone#ZONE ZoneObject The Zone to be tested for. -- @param Core.Zone#ZONE ZoneObject The Zone to be tested for.
@ -2353,6 +2380,7 @@ do -- SET_UNIT
end end
--- Iterate the SET_UNIT and call an iterator function for each **alive** UNIT, providing the UNIT and optional parameters. --- Iterate the SET_UNIT and call an iterator function for each **alive** UNIT, providing the UNIT and optional parameters.
-- @param #SET_UNIT self -- @param #SET_UNIT self
-- @param #function IteratorFunction The function that will be called when there is an alive UNIT in the SET_UNIT. The function needs to accept a UNIT parameter. -- @param #function IteratorFunction The function that will be called when there is an alive UNIT in the SET_UNIT. The function needs to accept a UNIT parameter.
@ -2406,6 +2434,7 @@ do -- SET_UNIT
end end
--- Iterate the SET_UNIT **sorted *per Threat Level** and call an iterator function for each **alive** UNIT, providing the UNIT and optional parameters. --- Iterate the SET_UNIT **sorted *per Threat Level** and call an iterator function for each **alive** UNIT, providing the UNIT and optional parameters.
-- --
-- @param #SET_UNIT self -- @param #SET_UNIT self
@ -2795,6 +2824,8 @@ do -- SET_UNIT
return FriendlyUnitCount return FriendlyUnitCount
end end
----- Iterate the SET_UNIT and call an iterator function for each **alive** player, providing the Unit of the player and optional parameters. ----- Iterate the SET_UNIT and call an iterator function for each **alive** player, providing the Unit of the player and optional parameters.
---- @param #SET_UNIT self ---- @param #SET_UNIT self
---- @param #function IteratorFunction The function that will be called when there is an alive player in the SET_UNIT. The function needs to accept a UNIT parameter. ---- @param #function IteratorFunction The function that will be called when there is an alive player in the SET_UNIT. The function needs to accept a UNIT parameter.
@ -3152,6 +3183,7 @@ do -- SET_STATIC
return self return self
end end
--- Builds a set of statics in zones. --- Builds a set of statics in zones.
-- @param #SET_STATIC self -- @param #SET_STATIC self
-- @param #table Zones Table of Core.Zone#ZONE Zone objects, or a Core.Set#SET_ZONE -- @param #table Zones Table of Core.Zone#ZONE Zone objects, or a Core.Set#SET_ZONE
@ -3374,6 +3406,7 @@ do -- SET_STATIC
end end
--- Iterate the SET_STATIC and call an iterator function for each **alive** STATIC, providing the STATIC and optional parameters. --- Iterate the SET_STATIC and call an iterator function for each **alive** STATIC, providing the STATIC and optional parameters.
-- @param #SET_STATIC self -- @param #SET_STATIC self
-- @param #function IteratorFunction The function that will be called when there is an alive STATIC in the SET_STATIC. The function needs to accept a STATIC parameter. -- @param #function IteratorFunction The function that will be called when there is an alive STATIC in the SET_STATIC. The function needs to accept a STATIC parameter.
@ -4080,6 +4113,26 @@ do -- SET_CLIENT
return CountU return CountU
end end
--- Gets the alive set.
-- @param #SET_CLIENT self
-- @return #table Table of SET objects
function SET_CLIENT:GetAliveSet()
local AliveSet = SET_CLIENT:New()
-- Clean the Set before returning with only the alive Groups.
for GroupName, GroupObject in pairs(self.Set) do
local GroupObject=GroupObject --Wrapper.Client#CLIENT
if GroupObject and GroupObject:IsAlive() then
AliveSet:Add(GroupName, GroupObject)
end
end
return AliveSet.Set or {}
end
--- ---
-- @param #SET_CLIENT self -- @param #SET_CLIENT self
-- @param Wrapper.Client#CLIENT MClient -- @param Wrapper.Client#CLIENT MClient
@ -4346,6 +4399,7 @@ do -- SET_PLAYER
return self return self
end end
--- Builds a set of clients out of categories joined by players. --- Builds a set of clients out of categories joined by players.
-- Possible current categories are plane, helicopter, ground, ship. -- Possible current categories are plane, helicopter, ground, ship.
-- @param #SET_PLAYER self -- @param #SET_PLAYER self
@ -5614,7 +5668,28 @@ do -- SET_ZONE
return self return self
end end
--- --- Draw all zones in the set on the F10 map.
-- @param #SET_ZONE self
-- @param #number Coalition Coalition: All=-1, Neutral=0, Red=1, Blue=2. Default -1=All.
-- @param #table Color RGB color table {r, g, b}, e.g. {1,0,0} for red.
-- @param #number Alpha Transparency [0,1]. Default 1.
-- @param #table FillColor RGB color table {r, g, b}, e.g. {1,0,0} for red. Default is same as `Color` value.
-- @param #number FillAlpha Transparency [0,1]. Default 0.15.
-- @param #number LineType Line type: 0=No line, 1=Solid, 2=Dashed, 3=Dotted, 4=Dot dash, 5=Long dash, 6=Two dash. Default 1=Solid.
-- @param #boolean ReadOnly (Optional) Mark is readonly and cannot be removed by users. Default false.
-- @return #SET_ZONE self
function SET_ZONE:DrawZone(Coalition, Color, Alpha, FillColor, FillAlpha, LineType, ReadOnly)
for _,_zone in pairs(self.Set) do
local zone=_zone --Core.Zone#ZONE
zone:DrawZone(Coalition, Color, Alpha, FillColor, FillAlpha, LineType, ReadOnly)
end
return self
end
--- Private function.
-- @param #SET_ZONE self -- @param #SET_ZONE self
-- @param Core.Zone#ZONE_BASE MZone -- @param Core.Zone#ZONE_BASE MZone
-- @return #SET_ZONE self -- @return #SET_ZONE self
@ -6014,6 +6089,8 @@ do -- SET_ZONE_GOAL
end end
do -- SET_OPSGROUP do -- SET_OPSGROUP
--- @type SET_OPSGROUP --- @type SET_OPSGROUP
@ -6119,9 +6196,10 @@ do -- SET_OPSGROUP
}, -- FilterMeta }, -- FilterMeta
} }
--- Creates a new SET_OPSGROUP object, building a set of groups belonging to a coalitions, categories, countries, types or with defined prefix names. --- Creates a new SET_OPSGROUP object, building a set of groups belonging to a coalitions, categories, countries, types or with defined prefix names.
-- @param #SET_OPSGROUP self -- @param #SET_OPSGROUP self
-- @return #SET_OPSGROUP -- @return #SET_OPSGROUP self
function SET_OPSGROUP:New() function SET_OPSGROUP:New()
-- Inherit SET_BASE. -- Inherit SET_BASE.
@ -6205,6 +6283,14 @@ do -- SET_OPSGROUP
self:Added(ObjectName, object) self:Added(ObjectName, object)
end end
--- Adds a @{Core.Base#BASE} object in the @{Core.Set#SET_BASE}, using the Object Name as the index.
-- @param #SET_BASE self
-- @param Ops.OpsGroup#OPSGROUP Object Ops group
-- @return Core.Base#BASE The added BASE Object.
function SET_OPSGROUP:AddObject(Object)
self:Add(Object.groupname, Object)
end
--- Add a GROUP or OPSGROUP object to the set. --- Add a GROUP or OPSGROUP object to the set.
-- **NOTE** that an OPSGROUP is automatically created from the GROUP if it does not exist already. -- **NOTE** that an OPSGROUP is automatically created from the GROUP if it does not exist already.
-- @param Core.Set#SET_OPSGROUP self -- @param Core.Set#SET_OPSGROUP self
@ -6276,6 +6362,7 @@ do -- SET_OPSGROUP
return GroupFound return GroupFound
end end
--- Finds a NAVYGROUP based on the group name. --- Finds a NAVYGROUP based on the group name.
-- @param #SET_OPSGROUP self -- @param #SET_OPSGROUP self
-- @param #string GroupName Name of the group. -- @param #string GroupName Name of the group.
@ -6310,6 +6397,7 @@ do -- SET_OPSGROUP
return self return self
end end
--- Builds a set of groups out of categories. --- Builds a set of groups out of categories.
-- --
-- Possible current categories are: -- Possible current categories are:
@ -6355,7 +6443,7 @@ do -- SET_OPSGROUP
return self return self
end end
--- Builds a set of groups out of aircraft category (planes and helicopters). --- Builds a set of groups out of aicraft category (planes and helicopters).
-- @param #SET_OPSGROUP self -- @param #SET_OPSGROUP self
-- @return #SET_OPSGROUP self -- @return #SET_OPSGROUP self
function SET_OPSGROUP:FilterCategoryAircraft() function SET_OPSGROUP:FilterCategoryAircraft()
@ -6403,6 +6491,7 @@ do -- SET_OPSGROUP
return self return self
end end
--- Builds a set of groups that contain the given string in their group name. --- Builds a set of groups that contain the given string in their group name.
-- **Attention!** Bad naming convention as this **does not** filter only **prefixes** but all groups that **contain** the string. -- **Attention!** Bad naming convention as this **does not** filter only **prefixes** but all groups that **contain** the string.
-- @param #SET_OPSGROUP self -- @param #SET_OPSGROUP self
@ -6431,7 +6520,7 @@ do -- SET_OPSGROUP
--- Builds a set of groups that are only active. --- Builds a set of groups that are only active.
-- Only the groups that are active will be included within the set. -- Only the groups that are active will be included within the set.
-- @param #SET_OPSGROUP self -- @param #SET_OPSGROUP self
-- @param #boolean Active (Optional) Include only active groups to the set. -- @param #boolean Active (optional) Include only active groups to the set.
-- Include inactive groups if you provide false. -- Include inactive groups if you provide false.
-- @return #SET_OPSGROUP self -- @return #SET_OPSGROUP self
-- @usage -- @usage
@ -6454,6 +6543,7 @@ do -- SET_OPSGROUP
return self return self
end end
--- Starts the filtering. --- Starts the filtering.
-- @param #SET_OPSGROUP self -- @param #SET_OPSGROUP self
-- @return #SET_OPSGROUP self -- @return #SET_OPSGROUP self

View File

@ -251,6 +251,7 @@ do -- SETTINGS
self:SetMessageTime( MESSAGE.Type.Overview, 60 ) self:SetMessageTime( MESSAGE.Type.Overview, 60 )
self:SetMessageTime( MESSAGE.Type.Update, 15 ) self:SetMessageTime( MESSAGE.Type.Update, 15 )
self:SetEraModern() self:SetEraModern()
self:SetLocale("en")
return self return self
else else
local Settings = _DATABASE:GetPlayerSettings( PlayerName ) local Settings = _DATABASE:GetPlayerSettings( PlayerName )
@ -283,6 +284,20 @@ do -- SETTINGS
self.Metric = true self.Metric = true
end end
--- Sets the SETTINGS default text locale.
-- @param #SETTINGS self
-- @param #string Locale
function SETTINGS:SetLocale(Locale)
self.Locale = Locale or "en"
end
--- Gets the SETTINGS text locale.
-- @param #SETTINGS self
-- @return #string
function SETTINGS:GetLocale()
return self.Locale or _SETTINGS:GetLocale()
end
--- Gets if the SETTINGS is metric. --- Gets if the SETTINGS is metric.
-- @param #SETTINGS self -- @param #SETTINGS self
-- @return #boolean true if metric. -- @return #boolean true if metric.

View File

@ -2403,8 +2403,7 @@ end
-- @param #SPAWN self -- @param #SPAWN self
-- @param DCS#Vec3 Vec3 The Vec3 coordinates where to spawn the group. -- @param DCS#Vec3 Vec3 The Vec3 coordinates where to spawn the group.
-- @param #number SpawnIndex (optional) The index which group to spawn within the given zone. -- @param #number SpawnIndex (optional) The index which group to spawn within the given zone.
-- @return Wrapper.Group#GROUP that was spawned. -- @return Wrapper.Group#GROUP that was spawned or #nil if nothing was spawned.
-- @return #nil Nothing was spawned.
function SPAWN:SpawnFromVec3( Vec3, SpawnIndex ) function SPAWN:SpawnFromVec3( Vec3, SpawnIndex )
self:F( { self.SpawnTemplatePrefix, Vec3, SpawnIndex } ) self:F( { self.SpawnTemplatePrefix, Vec3, SpawnIndex } )
@ -2472,8 +2471,7 @@ end
-- @param #SPAWN self -- @param #SPAWN self
-- @param Core.Point#Coordinate Coordinate The Coordinate coordinates where to spawn the group. -- @param Core.Point#Coordinate Coordinate The Coordinate coordinates where to spawn the group.
-- @param #number SpawnIndex (optional) The index which group to spawn within the given zone. -- @param #number SpawnIndex (optional) The index which group to spawn within the given zone.
-- @return Wrapper.Group#GROUP that was spawned. -- @return Wrapper.Group#GROUP that was spawned or #nil if nothing was spawned.
-- @return #nil Nothing was spawned.
function SPAWN:SpawnFromCoordinate( Coordinate, SpawnIndex ) function SPAWN:SpawnFromCoordinate( Coordinate, SpawnIndex )
self:F( { self.SpawnTemplatePrefix, SpawnIndex } ) self:F( { self.SpawnTemplatePrefix, SpawnIndex } )
@ -2487,8 +2485,7 @@ end
-- @param #SPAWN self -- @param #SPAWN self
-- @param Core.Point#POINT_VEC3 PointVec3 The PointVec3 coordinates where to spawn the group. -- @param Core.Point#POINT_VEC3 PointVec3 The PointVec3 coordinates where to spawn the group.
-- @param #number SpawnIndex (optional) The index which group to spawn within the given zone. -- @param #number SpawnIndex (optional) The index which group to spawn within the given zone.
-- @return Wrapper.Group#GROUP that was spawned. -- @return Wrapper.Group#GROUP that was spawned or #nil if nothing was spawned.
-- @return #nil Nothing was spawned.
-- @usage -- @usage
-- --
-- local SpawnPointVec3 = ZONE:New( ZoneName ):GetPointVec3( 2000 ) -- Get the center of the ZONE object at 2000 meters from the ground. -- local SpawnPointVec3 = ZONE:New( ZoneName ):GetPointVec3( 2000 ) -- Get the center of the ZONE object at 2000 meters from the ground.
@ -2511,8 +2508,7 @@ end
-- @param #number MinHeight (optional) The minimum height to spawn an airborne group into the zone. -- @param #number MinHeight (optional) The minimum height to spawn an airborne group into the zone.
-- @param #number MaxHeight (optional) The maximum height to spawn an airborne group into the zone. -- @param #number MaxHeight (optional) The maximum height to spawn an airborne group into the zone.
-- @param #number SpawnIndex (optional) The index which group to spawn within the given zone. -- @param #number SpawnIndex (optional) The index which group to spawn within the given zone.
-- @return Wrapper.Group#GROUP that was spawned. -- @return Wrapper.Group#GROUP that was spawned or #nil if nothing was spawned.
-- @return #nil Nothing was spawned.
-- @usage -- @usage
-- --
-- local SpawnVec2 = ZONE:New( ZoneName ):GetVec2() -- local SpawnVec2 = ZONE:New( ZoneName ):GetVec2()
@ -2544,8 +2540,7 @@ end
-- @param #number MinHeight (optional) The minimum height to spawn an airborne group into the zone. -- @param #number MinHeight (optional) The minimum height to spawn an airborne group into the zone.
-- @param #number MaxHeight (optional) The maximum height to spawn an airborne group into the zone. -- @param #number MaxHeight (optional) The maximum height to spawn an airborne group into the zone.
-- @param #number SpawnIndex (optional) The index which group to spawn within the given zone. -- @param #number SpawnIndex (optional) The index which group to spawn within the given zone.
-- @return Wrapper.Group#GROUP that was spawned. -- @return Wrapper.Group#GROUP that was spawned or #nil if nothing was spawned.
-- @return #nil Nothing was spawned.
-- @usage -- @usage
-- --
-- local SpawnPointVec2 = ZONE:New( ZoneName ):GetPointVec2() -- local SpawnPointVec2 = ZONE:New( ZoneName ):GetPointVec2()
@ -2599,8 +2594,7 @@ end
-- @param #number MinHeight (optional) The minimum height to spawn an airborne group into the zone. -- @param #number MinHeight (optional) The minimum height to spawn an airborne group into the zone.
-- @param #number MaxHeight (optional) The maximum height to spawn an airborne group into the zone. -- @param #number MaxHeight (optional) The maximum height to spawn an airborne group into the zone.
-- @param #number SpawnIndex (optional) The index which group to spawn within the given zone. -- @param #number SpawnIndex (optional) The index which group to spawn within the given zone.
-- @return Wrapper.Group#GROUP that was spawned. -- @return Wrapper.Group#GROUP that was spawned or #nil if nothing was spawned.
-- @return #nil Nothing was spawned.
-- @usage -- @usage
-- --
-- local SpawnStatic = STATIC:FindByName( StaticName ) -- local SpawnStatic = STATIC:FindByName( StaticName )
@ -2631,8 +2625,7 @@ end
-- @param #number MinHeight (optional) The minimum height to spawn an airborne group into the zone. -- @param #number MinHeight (optional) The minimum height to spawn an airborne group into the zone.
-- @param #number MaxHeight (optional) The maximum height to spawn an airborne group into the zone. -- @param #number MaxHeight (optional) The maximum height to spawn an airborne group into the zone.
-- @param #number SpawnIndex (optional) The index which group to spawn within the given zone. -- @param #number SpawnIndex (optional) The index which group to spawn within the given zone.
-- @return Wrapper.Group#GROUP that was spawned. -- @return Wrapper.Group#GROUP that was spawned or #nil if nothing was spawned.
-- @return #nil when nothing was spawned.
-- @usage -- @usage
-- --
-- local SpawnZone = ZONE:New( ZoneName ) -- local SpawnZone = ZONE:New( ZoneName )

View File

@ -0,0 +1,202 @@
--- **Core** - TEXTANDSOUND (MOOSE gettext) system
--
-- ===
--
-- ## Main Features:
--
-- * A GetText for Moose
-- * Build a set of localized text entries, alongside their sounds and subtitles
-- * Aimed at class developers to offer localizable language support
--
-- ===
--
-- ## Example Missions:
--
-- Demo missions can be found on [github](https://github.com/FlightControl-Master/MOOSE_MISSIONS/tree/develop/).
--
-- ===
--
-- ### Author: **applevangelist**
-- ## Date: April 2022
--
-- ===
--
-- @module Core.TextAndSound
-- @image MOOSE.JPG
--- Text and Sound class.
-- @type TEXTANDSOUND
-- @field #string ClassName Name of this class.
-- @field #string version Versioning.
-- @field #string lid LID for log entries.
-- @field #string locale Default locale of this object.
-- @field #table entries Table of entries.
-- @field #string textclass Name of the class the texts belong to.
-- @extends Core.Base#BASE
---
--
-- @field #TEXTANDSOUND
TEXTANDSOUND = {
ClassName = "TEXTANDSOUND",
version = "0.0.1",
lid = "",
locale = "en",
entries = {},
textclass = "",
}
--- Text and Sound entry.
-- @type TEXTANDSOUND.Entry
-- @field #string Classname Name of the class this entry is for.
-- @field #string Locale Locale of this entry, defaults to "en".
-- @field #table Data The list of entries.
--- Text and Sound data
-- @type TEXTANDSOUND.Data
-- @field #string ID ID of this entry for retrieval.
-- @field #string Text Text of this entry.
-- @field #string Soundfile (optional) Soundfile File name of the corresponding sound file.
-- @field #number Soundlength (optional) Length of the sound file in seconds.
-- @field #string Subtitle (optional) Subtitle for the sound file.
--- Instantiate a new object
-- @param #TEXTANDSOUND self
-- @param #string ClassName Name of the class this instance is providing texts for.
-- @param #string Defaultlocale (Optional) Default locale of this instance, defaults to "en".
-- @return #TEXTANDSOUND self
function TEXTANDSOUND:New(ClassName,Defaultlocale)
-- Inherit everything from BASE class.
local self=BASE:Inherit(self, BASE:New())
-- Set some string id for output to DCS.log file.
self.lid=string.format("%s (%s) | ", self.ClassName, self.version)
self.locale = Defaultlocale or (_SETTINGS:GetLocale() or "en")
self.textclass = ClassName or "none"
self.entries = {}
local initentry = {} -- #TEXTANDSOUND.Entry
initentry.Classname = ClassName
initentry.Data = {}
initentry.Locale = self.locale
self.entries[self.locale] = initentry
self:I(self.lid .. "Instantiated.")
self:T({self.entries[self.locale]})
return self
end
--- Add an entry
-- @param #TEXTANDSOUND self
-- @param #string Locale Locale to set for this entry, e.g. "de".
-- @param #string ID Unique(!) ID of this entry under this locale (i.e. use the same ID to get localized text for the entry in another language).
-- @param #string Text Text for this entry.
-- @param #string Soundfile (Optional) Sound file name for this entry.
-- @param #number Soundlength (Optional) Length of the sound file in seconds.
-- @param #string Subtitle (Optional) Subtitle to be used alongside the sound file.
-- @return #TEXTANDSOUND self
function TEXTANDSOUND:AddEntry(Locale,ID,Text,Soundfile,Soundlength,Subtitle)
self:T(self.lid .. "AddEntry")
local locale = Locale or self.locale
local dataentry = {} -- #TEXTANDSOUND.Data
dataentry.ID = ID or "1"
dataentry.Text = Text or "none"
dataentry.Soundfile = Soundfile
dataentry.Soundlength = Soundlength or 0
dataentry.Subtitle = Subtitle
if not self.entries[locale] then
local initentry = {} -- #TEXTANDSOUND.Entry
initentry.Classname = self.textclass -- class name entry
initentry.Data = {} -- data array
initentry.Locale = locale -- default locale
self.entries[locale] = initentry
end
self.entries[locale].Data[ID] = dataentry
self:T({self.entries[locale].Data})
return self
end
--- Get an entry
-- @param #TEXTANDSOUND self
-- @param #string ID The unique ID of the data to be retrieved.
-- @param #string Locale (Optional) The locale of the text to be retrieved - defauls to default locale set with `New()`.
-- @return #string Text Text or nil if not found and no fallback.
-- @return #string Soundfile Filename or nil if not found and no fallback.
-- @return #string Soundlength Length of the sound or 0 if not found and no fallback.
-- @return #string Subtitle Text for subtitle or nil if not found and no fallback.
function TEXTANDSOUND:GetEntry(ID,Locale)
self:T(self.lid .. "GetEntry")
local locale = Locale or self.locale
if not self.entries[locale] then
-- fall back to default "en"
locale = self.locale
end
local Text,Soundfile,Soundlength,Subtitle = nil, nil, 0, nil
if self.entries[locale] then
if self.entries[locale].Data then
local data = self.entries[locale].Data[ID] -- #TEXTANDSOUND.Data
if data then
Text = data.Text
Soundfile = data.Soundfile
Soundlength = data.Soundlength
Subtitle = data.Subtitle
elseif self.entries[self.locale].Data[ID] then
-- no matching entry, try default
local data = self.entries[self.locale].Data[ID]
Text = data.Text
Soundfile = data.Soundfile
Soundlength = data.Soundlength
Subtitle = data.Subtitle
end
end
else
return nil, nil, 0, nil
end
return Text,Soundfile,Soundlength,Subtitle
end
--- Get the default locale of this object
-- @param #TEXTANDSOUND self
-- @return #string locale
function TEXTANDSOUND:GetDefaultLocale()
self:T(self.lid .. "GetDefaultLocale")
return self.locale
end
--- Set default locale of this object
-- @param #TEXTANDSOUND self
-- @param #string locale
-- @return #TEXTANDSOUND self
function TEXTANDSOUND:SetDefaultLocale(locale)
self:T(self.lid .. "SetDefaultLocale")
self.locale = locale or "en"
return self
end
--- Check if a locale exists
-- @param #TEXTANDSOUND self
-- @return #boolean outcome
function TEXTANDSOUND:HasLocale(Locale)
self:T(self.lid .. "HasLocale")
return self.entries[Locale] and true or false
end
--- Flush all entries to the log
-- @param #TEXTANDSOUND self
-- @return #TEXTANDSOUND self
function TEXTANDSOUND:FlushToLog()
self:I(self.lid .. "Flushing entries:")
local text = string.format("Textclass: %s | Default Locale: %s",self.textclass, self.locale)
for _,_entry in pairs(self.entries) do
local entry = _entry -- #TEXTANDSOUND.Entry
local text = string.format("Textclassname: %s | Locale: %s",entry.Classname, entry.Locale)
self:I(text)
for _ID,_data in pairs(entry.Data) do
local data = _data -- #TEXTANDSOUND.Data
local text = string.format("ID: %s\nText: %s\nSoundfile: %s With length: %d\nSubtitle: %s",tostring(_ID), data.Text or "none",data.Soundfile or "none",data.Soundlength or 0,data.Subtitle or "none")
self:I(text)
end
end
return self
end
----------------------------------------------------------------
-- End TextAndSound
----------------------------------------------------------------

View File

@ -34,8 +34,6 @@
-- --
-- === -- ===
-- --
-- ![Banner Image](..\Presentations\Timer\TIMER_Main.jpg)
--
-- # The TIMER Concept -- # The TIMER Concept
-- --
-- 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. -- 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.
@ -107,19 +105,17 @@ TIMER = {
--- Timer ID. --- Timer ID.
_TIMERID=0 _TIMERID=0
--- Timer data base.
--_TIMERDB={}
--- TIMER class version. --- TIMER class version.
-- @field #string version -- @field #string version
TIMER.version="0.1.1" TIMER.version="0.1.2"
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO list -- TODO list
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO: A lot. -- TODO: Randomization.
-- TODO: Write docs. -- TODO: Pause/unpause.
-- DONE: Write docs.
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Constructor -- Constructor
@ -156,9 +152,6 @@ function TIMER:New(Function, ...)
-- Log id. -- Log id.
self.lid=string.format("TIMER UID=%d | ", self.uid) self.lid=string.format("TIMER UID=%d | ", self.uid)
-- Add to DB.
--_TIMERDB[self.uid]=self
return self return self
end end
@ -174,7 +167,7 @@ function TIMER:Start(Tstart, dT, Duration)
local Tnow=timer.getTime() local Tnow=timer.getTime()
-- Start time in sec. -- Start time in sec.
self.Tstart=Tstart and Tnow+Tstart or Tnow+0.001 -- one millisecond delay if Tstart=nil self.Tstart=Tstart and Tnow+math.max(Tstart, 0.001) or Tnow+0.001 -- one millisecond delay if Tstart=nil
-- Set time interval. -- Set time interval.
self.dT=dT self.dT=dT
@ -220,9 +213,6 @@ function TIMER:Stop(Delay)
-- Not running any more. -- Not running any more.
self.isrunning=false self.isrunning=false
-- Remove DB entry.
--_TIMERDB[self.uid]=nil
end end
end end
@ -239,6 +229,15 @@ function TIMER:SetMaxFunctionCalls(Nmax)
return self return self
end end
--- Set time interval. Can also be set when the timer is already running and is applied after the next function call.
-- @param #TIMER self
-- @param #number dT Time interval in seconds.
-- @return #TIMER self
function TIMER:SetTimeInterval(dT)
self.dT=dT
return self
end
--- Check if the timer has been started and was not stopped. --- Check if the timer has been started and was not stopped.
-- @param #TIMER self -- @param #TIMER self
-- @return #boolean If `true`, the timer is running. -- @return #boolean If `true`, the timer is running.

View File

@ -59,7 +59,11 @@
-- @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 #number DrawID Unique ID of the drawn zone on the F10 map. -- @field #number DrawID Unique ID of the drawn zone on the F10 map.
-- @field #table Color Table with four entries, e.g. {1, 0, 0, 0.15}. First three are RGB color code. Fourth is the transparency Alpha value. -- @field #table Color Table with four entries, e.g. {1, 0, 0, 0.15}. First three are RGB color code. Fourth is the transparency Alpha value.
-- @field #table FillColor Table with four entries, e.g. {1, 0, 0, 0.15}. First three are RGB color code. Fourth is the transparency Alpha value.
-- @field #number drawCoalition Draw coalition.
-- @field #number ZoneID ID of zone. Only zones defined in the ME have an ID! -- @field #number ZoneID ID of zone. Only zones defined in the ME have an ID!
-- @field #table Table of any trigger zone properties from the ME. The key is the Name of the property, and the value is the property's Value.
-- @field #number Surface Type of surface. Only determined at the center of the zone!
-- @extends Core.Fsm#FSM -- @extends Core.Fsm#FSM
@ -103,6 +107,11 @@
-- * @{#ZONE_BASE.SmokeZone}(): Smokes the zone boundaries in a color. -- * @{#ZONE_BASE.SmokeZone}(): Smokes the zone boundaries in a color.
-- * @{#ZONE_BASE.FlareZone}(): Flares the zone boundaries in a color. -- * @{#ZONE_BASE.FlareZone}(): Flares the zone boundaries in a color.
-- --
-- ## A zone might have additional Properties created in the DCS Mission Editor, which can be accessed:
--
-- *@{#ZONE_BASE.GetProperty}(): Returns the Value of the zone with the given PropertyName, or nil if no matching property exists.
-- *@{#ZONE_BASE.GetAllProperties}(): Returns the zone Properties table.
--
-- @field #ZONE_BASE -- @field #ZONE_BASE
ZONE_BASE = { ZONE_BASE = {
ClassName = "ZONE_BASE", ClassName = "ZONE_BASE",
@ -111,6 +120,8 @@ ZONE_BASE = {
DrawID=nil, DrawID=nil,
Color={}, Color={},
ZoneID=nil, ZoneID=nil,
Properties={},
Sureface=nil,
} }
@ -336,18 +347,41 @@ end
-- @param #ZONE_BASE self -- @param #ZONE_BASE self
-- @return #nil The bounding square. -- @return #nil The bounding square.
function ZONE_BASE:GetBoundingSquare() function ZONE_BASE:GetBoundingSquare()
--return { x1 = 0, y1 = 0, x2 = 0, y2 = 0 }
return nil return nil
end end
--- Get surface type of the zone.
-- @param #ZONE_BASE self
-- @return DCS#SurfaceType Type of surface.
function ZONE_BASE:GetSurfaceType()
local coord=self:GetCoordinate()
local surface=coord:GetSurfaceType()
return surface
end
--- Bound the zone boundaries with a tires. --- Bound the zone boundaries with a tires.
-- @param #ZONE_BASE self -- @param #ZONE_BASE self
function ZONE_BASE:BoundZone() function ZONE_BASE:BoundZone()
self:F2() self:F2()
end end
--- Set draw coalition of zone.
-- @param #ZONE_BASE self
-- @param #number Coalition Coalition. Default -1.
-- @return #ZONE_BASE self
function ZONE_BASE:SetDrawCoalition(Coalition)
self.drawCoalition=Coalition or -1
return self
end
--- Get draw coalition of zone.
-- @param #ZONE_BASE self
-- @return #number Draw coaliton.
function ZONE_BASE:GetDrawCoalition()
return self.drawCoalition or -1
end
--- Set color of zone. --- Set color of zone.
-- @param #ZONE_BASE self -- @param #ZONE_BASE self
-- @param #table RGBcolor RGB color table. Default `{1, 0, 0}`. -- @param #table RGBcolor RGB color table. Default `{1, 0, 0}`.
@ -371,7 +405,7 @@ end
-- @param #ZONE_BASE self -- @param #ZONE_BASE self
-- @return #table Table with four entries, e.g. {1, 0, 0, 0.15}. First three are RGB color code. Fourth is the transparency Alpha value. -- @return #table Table with four entries, e.g. {1, 0, 0, 0.15}. First three are RGB color code. Fourth is the transparency Alpha value.
function ZONE_BASE:GetColor() function ZONE_BASE:GetColor()
return self.Color return self.Color or {1, 0, 0, 0.15}
end end
--- Get RGB color of zone. --- Get RGB color of zone.
@ -379,9 +413,10 @@ end
-- @return #table Table with three entries, e.g. {1, 0, 0}, which is the RGB color code. -- @return #table Table with three entries, e.g. {1, 0, 0}, which is the RGB color code.
function ZONE_BASE:GetColorRGB() function ZONE_BASE:GetColorRGB()
local rgb={} local rgb={}
rgb[1]=self.Color[1] local Color=self:GetColor()
rgb[2]=self.Color[2] rgb[1]=Color[1]
rgb[3]=self.Color[3] rgb[2]=Color[2]
rgb[3]=Color[3]
return rgb return rgb
end end
@ -389,7 +424,55 @@ end
-- @param #ZONE_BASE self -- @param #ZONE_BASE self
-- @return #number Alpha value. -- @return #number Alpha value.
function ZONE_BASE:GetColorAlpha() function ZONE_BASE:GetColorAlpha()
local alpha=self.Color[4] local Color=self:GetColor()
local alpha=Color[4]
return alpha
end
--- Set fill color of zone.
-- @param #ZONE_BASE self
-- @param #table RGBcolor RGB color table. Default `{1, 0, 0}`.
-- @param #number Alpha Transparacy between 0 and 1. Default 0.15.
-- @return #ZONE_BASE self
function ZONE_BASE:SetFillColor(RGBcolor, Alpha)
RGBcolor=RGBcolor or {1, 0, 0}
Alpha=Alpha or 0.15
self.FillColor={}
self.FillColor[1]=RGBcolor[1]
self.FillColor[2]=RGBcolor[2]
self.FillColor[3]=RGBcolor[3]
self.FillColor[4]=Alpha
return self
end
--- Get fill color table of the zone.
-- @param #ZONE_BASE self
-- @return #table Table with four entries, e.g. {1, 0, 0, 0.15}. First three are RGB color code. Fourth is the transparency Alpha value.
function ZONE_BASE:GetFillColor()
return self.FillColor or {1, 0, 0, 0.15}
end
--- Get RGB fill color of zone.
-- @param #ZONE_BASE self
-- @return #table Table with three entries, e.g. {1, 0, 0}, which is the RGB color code.
function ZONE_BASE:GetFillColorRGB()
local rgb={}
local FillColor=self:GetFillColor()
rgb[1]=FillColor[1]
rgb[2]=FillColor[2]
rgb[3]=FillColor[3]
return rgb
end
--- Get transperency Alpha fill value of zone.
-- @param #ZONE_BASE self
-- @return #number Alpha value.
function ZONE_BASE:GetFillColorAlpha()
local FillColor=self:GetFillColor()
local alpha=FillColor[4]
return alpha return alpha
end end
@ -481,6 +564,26 @@ function ZONE_BASE:GetZoneMaybe()
end end
end end
-- Returns the Value of the zone with the given PropertyName, or nil if no matching property exists.
-- @param #ZONE_BASE self
-- @param #string PropertyName The name of a the TriggerZone Property to be retrieved.
-- @return #string The Value of the TriggerZone Property with the given PropertyName, or nil if absent.
-- @usage
--
-- local PropertiesZone = ZONE:FindByName("Properties Zone")
-- local Property = "ExampleProperty"
-- local PropertyValue = PropertiesZone:GetProperty(Property)
--
function ZONE_BASE:GetProperty(PropertyName)
return self.Properties[PropertyName]
end
-- Returns the zone Properties table.
-- @param #ZONE_BASE self
-- @return #table The Key:Value table of TriggerZone properties of the zone.
function ZONE_BASE:GetAllProperties()
return self.Properties
end
--- The ZONE_RADIUS class, defined by a zone name, a location and a radius. --- The ZONE_RADIUS class, defined by a zone name, a location and a radius.
-- @type ZONE_RADIUS -- @type ZONE_RADIUS
@ -823,8 +926,8 @@ end
-- @param ObjectCategories An array of categories of the objects to find in the zone. E.g. `{Object.Category.UNIT}` -- @param ObjectCategories An array of categories of the objects to find in the zone. E.g. `{Object.Category.UNIT}`
-- @param UnitCategories An array of unit categories of the objects to find in the zone. E.g. `{Unit.Category.GROUND_UNIT,Unit.Category.SHIP}` -- @param UnitCategories An array of unit categories of the objects to find in the zone. E.g. `{Unit.Category.GROUND_UNIT,Unit.Category.SHIP}`
-- @usage -- @usage
-- self.Zone:Scan({Object.Category.UNIT},{Unit.Category.GROUND_UNIT}) -- myzone:Scan({Object.Category.UNIT},{Unit.Category.GROUND_UNIT})
-- local IsAttacked = self.Zone:IsSomeInZoneOfCoalition( self.Coalition ) -- local IsAttacked = myzone:IsSomeInZoneOfCoalition( self.Coalition )
function ZONE_RADIUS:Scan( ObjectCategories, UnitCategories ) function ZONE_RADIUS:Scan( ObjectCategories, UnitCategories )
self.ScanData = {} self.ScanData = {}
@ -894,7 +997,7 @@ function ZONE_RADIUS:Scan( ObjectCategories, UnitCategories )
local SceneryName = ZoneObject:getName() local SceneryName = ZoneObject:getName()
self.ScanData.Scenery[SceneryType] = self.ScanData.Scenery[SceneryType] or {} self.ScanData.Scenery[SceneryType] = self.ScanData.Scenery[SceneryType] or {}
self.ScanData.Scenery[SceneryType][SceneryName] = SCENERY:Register( SceneryName, ZoneObject ) self.ScanData.Scenery[SceneryType][SceneryName] = SCENERY:Register( SceneryName, ZoneObject )
self:F2( { SCENERY = self.ScanData.Scenery[SceneryType][SceneryName] } ) self:T( { SCENERY = self.ScanData.Scenery[SceneryType][SceneryName] } )
end end
end end
@ -1157,7 +1260,9 @@ end
-- @return #boolean true if the location is within the zone. -- @return #boolean true if the location is within the zone.
function ZONE_RADIUS:IsVec2InZone( Vec2 ) function ZONE_RADIUS:IsVec2InZone( Vec2 )
self:F2( Vec2 ) self:F2( Vec2 )
if not Vec2 then return false end if not Vec2 then return false end
local ZoneVec2 = self:GetVec2() local ZoneVec2 = self:GetVec2()
if ZoneVec2 then if ZoneVec2 then
@ -1282,8 +1387,8 @@ end
--- Returns a @{Core.Point#COORDINATE} object reflecting a random 3D location within the zone. --- Returns a @{Core.Point#COORDINATE} object reflecting a random 3D location within the zone.
-- @param #ZONE_RADIUS self -- @param #ZONE_RADIUS self
-- @param #number inner (Optional) Minimal distance from the center of the zone. Default is 0. -- @param #number inner (Optional) Minimal distance from the center of the zone in meters. Default is 0 m.
-- @param #number outer (Optional) Maximal distance from the outer edge of the zone. Default is the radius of the zone. -- @param #number outer (Optional) Maximal distance from the outer edge of the zone in meters. Default is the radius of the zone.
-- @param #table surfacetypes (Optional) Table of surface types. Can also be a single surface type. We will try max 1000 times to find the right type! -- @param #table surfacetypes (Optional) Table of surface types. Can also be a single surface type. We will try max 1000 times to find the right type!
-- @return Core.Point#COORDINATE The random coordinate. -- @return Core.Point#COORDINATE The random coordinate.
function ZONE_RADIUS:GetRandomCoordinate(inner, outer, surfacetypes) function ZONE_RADIUS:GetRandomCoordinate(inner, outer, surfacetypes)
@ -1450,9 +1555,9 @@ function ZONE:New( ZoneName )
end end
--- Find a zone in the _DATABASE using the name of the zone. --- Find a zone in the _DATABASE using the name of the zone.
-- @param #ZONE_BASE self -- @param #ZONE self
-- @param #string ZoneName The name of the zone. -- @param #string ZoneName The name of the zone.
-- @return #ZONE_BASE self -- @return #ZONE self
function ZONE:FindByName( ZoneName ) function ZONE:FindByName( ZoneName )
local ZoneFound = _DATABASE:FindZone( ZoneName ) local ZoneFound = _DATABASE:FindZone( ZoneName )
@ -1688,7 +1793,7 @@ end
--- @type ZONE_POLYGON_BASE --- @type ZONE_POLYGON_BASE
-- --@field #ZONE_POLYGON_BASE.ListVec2 Polygon The polygon defined by an array of @{DCS#Vec2}. -- @field #ZONE_POLYGON_BASE.ListVec2 Polygon The polygon defined by an array of @{DCS#Vec2}.
-- @extends #ZONE_BASE -- @extends #ZONE_BASE
@ -1926,7 +2031,7 @@ function ZONE_POLYGON_BASE:BoundZone( UnBound )
end end
--- Draw the zone on the F10 map. **NOTE** Currently, only polygons with **exactly four points** are supported! --- Draw the zone on the F10 map. **NOTE** Currently, only polygons **up to ten points** are supported!
-- @param #ZONE_POLYGON_BASE self -- @param #ZONE_POLYGON_BASE self
-- @param #number Coalition Coalition: All=-1, Neutral=0, Red=1, Blue=2. Default -1=All. -- @param #number Coalition Coalition: All=-1, Neutral=0, Red=1, Blue=2. Default -1=All.
-- @param #table Color RGB color table {r, g, b}, e.g. {1,0,0} for red. -- @param #table Color RGB color table {r, g, b}, e.g. {1,0,0} for red.
@ -1938,14 +2043,28 @@ end
-- @return #ZONE_POLYGON_BASE self -- @return #ZONE_POLYGON_BASE self
function ZONE_POLYGON_BASE:DrawZone(Coalition, Color, Alpha, FillColor, FillAlpha, LineType, ReadOnly) function ZONE_POLYGON_BASE:DrawZone(Coalition, Color, Alpha, FillColor, FillAlpha, LineType, ReadOnly)
if self._.Polygon and #self._.Polygon>=3 then
local coordinate=COORDINATE:NewFromVec2(self._.Polygon[1]) local coordinate=COORDINATE:NewFromVec2(self._.Polygon[1])
Coalition=Coalition or self:GetDrawCoalition()
-- Set draw coalition.
self:SetDrawCoalition(Coalition)
Color=Color or self:GetColorRGB() Color=Color or self:GetColorRGB()
Alpha=Alpha or 1 Alpha=Alpha or 1
FillColor=FillColor or UTILS.DeepCopy(Color) -- Set color.
FillAlpha=FillAlpha or self:GetColorAlpha() self:SetColor(Color, Alpha)
FillColor=FillColor or self:GetFillColorRGB()
if not FillColor then UTILS.DeepCopy(Color) end
FillAlpha=FillAlpha or self:GetFillColorAlpha()
if not FillAlpha then FillAlpha=0.15 end
-- Set fill color.
self:SetFillColor(FillColor, FillAlpha)
if #self._.Polygon==4 then if #self._.Polygon==4 then
@ -1964,6 +2083,7 @@ function ZONE_POLYGON_BASE:DrawZone(Coalition, Color, Alpha, FillColor, FillAlph
end end
end
return self return self
end end
@ -2297,6 +2417,206 @@ function ZONE_POLYGON:FindByName( ZoneName )
return ZoneFound return ZoneFound
end end
do -- ZONE_ELASTIC
--- @type ZONE_ELASTIC
-- @field #table points Points in 2D.
-- @field #table setGroups Set of GROUPs.
-- @field #table setOpsGroups Set of OPSGROUPS.
-- @field #table setUnits Set of UNITs.
-- @field #number updateID Scheduler ID for updating.
-- @extends #ZONE_POLYGON_BASE
--- The ZONE_ELASTIC class defines a dynamic polygon zone, where only the convex hull is used.
--
-- @field #ZONE_ELASTIC
ZONE_ELASTIC = {
ClassName="ZONE_ELASTIC",
points={},
setGroups={}
}
--- Constructor to create a ZONE_ELASTIC instance.
-- @param #ZONE_ELASTIC self
-- @param #string ZoneName Name of the zone.
-- @param DCS#Vec2 Points (Optional) Fixed points.
-- @return #ZONE_ELASTIC self
function ZONE_ELASTIC:New(ZoneName, Points)
local self=BASE:Inherit(self, ZONE_POLYGON_BASE:New(ZoneName, Points)) --#ZONE_ELASTIC
-- Zone objects are added to the _DATABASE and SET_ZONE objects.
_EVENTDISPATCHER:CreateEventNewZone( self )
if Points then
self.points=Points
end
return self
end
--- Add a vertex (point) to the polygon.
-- @param #ZONE_ELASTIC self
-- @param DCS#Vec2 Vec2 Point in 2D (with x and y coordinates).
-- @return #ZONE_ELASTIC self
function ZONE_ELASTIC:AddVertex2D(Vec2)
-- Add vec2 to points.
table.insert(self.points, Vec2)
return self
end
--- Add a vertex (point) to the polygon.
-- @param #ZONE_ELASTIC self
-- @param DCS#Vec3 Vec3 Point in 3D (with x, y and z coordinates). Only the x and z coordinates are used.
-- @return #ZONE_ELASTIC self
function ZONE_ELASTIC:AddVertex3D(Vec3)
-- Add vec2 from vec3 to points.
table.insert(self.points, {x=Vec3.x, y=Vec3.z})
return self
end
--- Add a set of groups. Positions of the group will be considered as polygon vertices when contructing the convex hull.
-- @param #ZONE_ELASTIC self
-- @param Core.Set#SET_GROUP SetGroup Set of groups.
-- @return #ZONE_ELASTIC self
function ZONE_ELASTIC:AddSetGroup(GroupSet)
-- Add set to table.
table.insert(self.setGroups, GroupSet)
return self
end
--- Update the convex hull of the polygon.
-- This uses the [Graham scan](https://en.wikipedia.org/wiki/Graham_scan).
-- @param #ZONE_ELASTIC self
-- @param #number Delay Delay in seconds before the zone is updated. Default 0.
-- @param #boolean Draw Draw the zone. Default `nil`.
-- @return #ZONE_ELASTIC self
function ZONE_ELASTIC:Update(Delay, Draw)
-- Debug info.
self:T(string.format("Updating ZONE_ELASTIC %s", tostring(self.ZoneName)))
-- Copy all points.
local points=UTILS.DeepCopy(self.points or {})
if self.setGroups then
for _,_setGroup in pairs(self.setGroups) do
local setGroup=_setGroup --Core.Set#SET_GROUP
for _,_group in pairs(setGroup.Set) do
local group=_group --Wrapper.Group#GROUP
if group and group:IsAlive() then
table.insert(points, group:GetVec2())
end
end
end
end
-- Update polygon verticies from points.
self._.Polygon=self:_ConvexHull(points)
if Draw~=false then
if self.DrawID or Draw==true then
self:UndrawZone()
self:DrawZone()
end
end
return self
end
--- Start the updating scheduler.
-- @param #ZONE_ELASTIC self
-- @param #number Tstart Time in seconds before the updating starts.
-- @param #number dT Time interval in seconds between updates. Default 60 sec.
-- @param #number Tstop Time in seconds after which the updating stops. Default `nil`.
-- @param #boolean Draw Draw the zone. Default `nil`.
-- @return #ZONE_ELASTIC self
function ZONE_ELASTIC:StartUpdate(Tstart, dT, Tstop, Draw)
self.updateID=self:ScheduleRepeat(Tstart, dT, 0, Tstop, ZONE_ELASTIC.Update, self, 0, Draw)
return self
end
--- Stop the updating scheduler.
-- @param #ZONE_ELASTIC self
-- @param #number Delay Delay in seconds before the scheduler will be stopped. Default 0.
-- @return #ZONE_ELASTIC self
function ZONE_ELASTIC:StopUpdate(Delay)
if Delay and Delay>0 then
self:ScheduleOnce(Delay, ZONE_ELASTIC.StopUpdate, self)
else
if self.updateID then
self:ScheduleStop(self.updateID)
self.updateID=nil
end
end
return self
end
--- Create a convec hull.
-- @param #ZONE_ELASTIC self
-- @param #table pl Points
-- @return #table Points
function ZONE_ELASTIC:_ConvexHull(pl)
if #pl == 0 then
return {}
end
table.sort(pl, function(left,right)
return left.x < right.x
end)
local h = {}
-- Function: ccw > 0 if three points make a counter-clockwise turn, clockwise if ccw < 0, and collinear if ccw = 0.
local function ccw(a,b,c)
return (b.x - a.x) * (c.y - a.y) > (b.y - a.y) * (c.x - a.x)
end
-- lower hull
for i,pt in pairs(pl) do
while #h >= 2 and not ccw(h[#h-1], h[#h], pt) do
table.remove(h,#h)
end
table.insert(h,pt)
end
-- upper hull
local t = #h + 1
for i=#pl, 1, -1 do
local pt = pl[i]
while #h >= t and not ccw(h[#h-1], h[#h], pt) do
table.remove(h, #h)
end
table.insert(h, pt)
end
table.remove(h, #h)
return h
end
end
do -- ZONE_AIRBASE do -- ZONE_AIRBASE
--- @type ZONE_AIRBASE --- @type ZONE_AIRBASE

View File

@ -667,7 +667,8 @@ do -- DETECTION_BASE
local Distance = ( ( DetectedObjectVec3.x - DetectionGroupVec3.x )^2 + local Distance = ( ( DetectedObjectVec3.x - DetectionGroupVec3.x )^2 +
( DetectedObjectVec3.y - DetectionGroupVec3.y )^2 + ( DetectedObjectVec3.y - DetectionGroupVec3.y )^2 +
(DetectedObjectVec3.z - DetectionGroupVec3.z) ^ 2) ^ 0.5 / 1000 ( DetectedObjectVec3.z - DetectionGroupVec3.z )^2
) ^ 0.5 / 1000
local DetectedUnitCategory = DetectedObject:getDesc().category local DetectedUnitCategory = DetectedObject:getDesc().category
@ -2440,7 +2441,7 @@ do -- DETECTION_AREAS
-- --
-- ## 4.1) Retrieve the Detected Unit Sets and Detected Zones -- ## 4.1) Retrieve the Detected Unit Sets and Detected Zones
-- --
-- The methods to manage the DetectedItems[].Set(s) are implemented in @{Functional.Detection#DETECTION_BASE} and -- The methods to manage the DetectedItems[].Set(s) are implemented in @{Functional.Detection#DECTECTION_BASE} and
-- the methods to manage the DetectedItems[].Zone(s) are implemented in @{Functional.Detection#DETECTION_AREAS}. -- the methods to manage the DetectedItems[].Zone(s) are implemented in @{Functional.Detection#DETECTION_AREAS}.
-- --
-- Retrieve the DetectedItems[].Set with the method @{Functional.Detection#DETECTION_BASE.GetDetectedSet}(). A @{Core.Set#SET_UNIT} object will be returned. -- Retrieve the DetectedItems[].Set with the method @{Functional.Detection#DETECTION_BASE.GetDetectedSet}(). A @{Core.Set#SET_UNIT} object will be returned.

View File

@ -792,7 +792,7 @@ function FOX:onafterMissileLaunch(From, Event, To, missile)
local text=string.format("Missile launch detected! Distance %.1f NM, bearing %03d°.", UTILS.MetersToNM(distance), bearing) local text=string.format("Missile launch detected! Distance %.1f NM, bearing %03d°.", UTILS.MetersToNM(distance), bearing)
-- Say notching headings. -- Say notching headings.
BASE:ScheduleOnce(5, FOX._SayNotchingHeadings, self, player, missile.weapon) self:ScheduleOnce(5, FOX._SayNotchingHeadings, self, player, missile.weapon)
--TODO: ALERT or INFO depending on whether this is a direct target. --TODO: ALERT or INFO depending on whether this is a direct target.
--TODO: lauchalertall option. --TODO: lauchalertall option.
@ -1114,6 +1114,13 @@ end
-- Event Functions -- Event Functions
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- FOX event handler for event birth.
-- @param #FOX self
-- @param Core.Event#EVENTDATA EventData
function FOX:OnEventPlayerEnterAircraft(EventData)
end
--- FOX event handler for event birth. --- FOX event handler for event birth.
-- @param #FOX self -- @param #FOX self
-- @param Core.Event#EVENTDATA EventData -- @param Core.Event#EVENTDATA EventData
@ -1155,7 +1162,7 @@ function FOX:OnEventBirth(EventData)
-- Add F10 radio menu for player. -- Add F10 radio menu for player.
if not self.menudisabled then if not self.menudisabled then
SCHEDULER:New(nil, self._AddF10Commands, {self,_unitName}, 0.1) self:ScheduleOnce(0.1, FOX._AddF10Commands, self, _unitname)
end end
-- Player data. -- Player data.

File diff suppressed because it is too large Load Diff

View File

@ -5,7 +5,7 @@
-- ## Features: -- ## Features:
-- --
-- * Track the missiles fired at you and other players, providing bearing and range information of the missiles towards the airplanes. -- * Track the missiles fired at you and other players, providing bearing and range information of the missiles towards the airplanes.
-- * Provide alerts of missile launches, including detailed information of the units launching, including bearing, range ° -- * Provide alerts of missile launches, including detailed information of the units launching, including bearing, range
-- * Provide alerts when a missile would have killed your aircraft. -- * Provide alerts when a missile would have killed your aircraft.
-- * Provide alerts when the missile self destructs. -- * Provide alerts when the missile self destructs.
-- * Enable / Disable and Configure the Missile Trainer using the various menu options. -- * Enable / Disable and Configure the Missile Trainer using the various menu options.

View File

@ -1044,6 +1044,3 @@ function PSEUDOATC:_myname(unitname)
return string.format("%s (%s)", csign, pname) return string.format("%s (%s)", csign, pname)
end end

View File

@ -2049,9 +2049,15 @@ function RAT:_InitAircraft(DCSgroup)
--self.aircraft.descriptors=DCSdesc --self.aircraft.descriptors=DCSdesc
-- aircraft dimensions -- aircraft dimensions
if DCSdesc.box then
self.aircraft.length=DCSdesc.box.max.x self.aircraft.length=DCSdesc.box.max.x
self.aircraft.height=DCSdesc.box.max.y self.aircraft.height=DCSdesc.box.max.y
self.aircraft.width=DCSdesc.box.max.z self.aircraft.width=DCSdesc.box.max.z
elseif DCStype == "Mirage-F1CE" then
self.aircraft.length=16
self.aircraft.height=5
self.aircraft.width=9
end
self.aircraft.box=math.max(self.aircraft.length,self.aircraft.width) self.aircraft.box=math.max(self.aircraft.length,self.aircraft.width)
-- info message -- info message
@ -5371,7 +5377,7 @@ function RAT:_ModifySpawnTemplate(waypoints, livery, spawnplace, departure, take
if spawnonground then if spawnonground then
-- Sh°ps and FARPS seem to have a build in queue. -- Ships and FARPS seem to have a build in queue.
if spawnonship or spawnonfarp or spawnonrunway or automatic then if spawnonship or spawnonfarp or spawnonrunway or automatic then
self:T(RAT.id..string.format("RAT group %s spawning at farp, ship or runway %s.", self.alias, departure:GetName())) self:T(RAT.id..string.format("RAT group %s spawning at farp, ship or runway %s.", self.alias, departure:GetName()))
@ -6145,4 +6151,3 @@ function RATMANAGER:_RollDice(nrat,ntot,min,alive)
-- Return number of groups to be spawned. -- Return number of groups to be spawned.
return N return N
end end

View File

@ -429,6 +429,25 @@ RANGE.TargetType = {
-- @field #string airframe Aircraft type of player. -- @field #string airframe Aircraft type of player.
-- @field #number time Time via timer.getAbsTime() in seconds of impact. -- @field #number time Time via timer.getAbsTime() in seconds of impact.
-- @field #string date OS date. -- @field #string date OS date.
-- @field #number attackHdg Attack heading in degrees.
-- @field #number attackVel Attack velocity in knots.
-- @field #number attackAlt Attack altitude in feet.
-- @field #string clock Time of the run.
-- @field #string rangename Name of the range.
--- Strafe result.
-- @type RANGE.StrafeResult
-- @field #string player Player name.
-- @field #string airframe Aircraft type of player.
-- @field #number time Time via timer.getAbsTime() in seconds of impact.
-- @field #string date OS date.
-- @field #string name Name of the target pit.
-- @field #number roundsFired Number of rounds fired.
-- @field #number roundsHit Number of rounds that hit the target.
-- @field #number strafeAccuracy Accuracy of the run in percent.
-- @field #string clock Time of the run.
-- @field #string rangename Name of the range.
-- @field #boolean invalid Invalid pass.
--- Strafe result. --- Strafe result.
-- @type RANGE.StrafeResult -- @type RANGE.StrafeResult
@ -569,17 +588,16 @@ RANGE.version = "2.4.0"
--- RANGE contructor. Creates a new RANGE object. --- RANGE contructor. Creates a new RANGE object.
-- @param #RANGE self -- @param #RANGE self
-- @param #string rangename Name of the range. Has to be unique. Will we used to create F10 menu items etc. -- @param #string RangeName Name of the range. Has to be unique. Will we used to create F10 menu items etc.
-- @return #RANGE RANGE object. -- @return #RANGE RANGE object.
function RANGE:New( rangename ) function RANGE:New( RangeName )
BASE:F( { rangename = rangename } )
-- Inherit BASE. -- Inherit BASE.
local self = BASE:Inherit( self, FSM:New() ) -- #RANGE local self = BASE:Inherit( self, FSM:New() ) -- #RANGE
-- Get range name. -- Get range name.
-- TODO: make sure that the range name is not given twice. This would lead to problems in the F10 radio menu. -- TODO: make sure that the range name is not given twice. This would lead to problems in the F10 radio menu.
self.rangename = rangename or "Practice Range" self.rangename = RangeName or "Practice Range"
-- Log id. -- Log id.
self.id = string.format( "RANGE %s | ", self.rangename ) self.id = string.format( "RANGE %s | ", self.rangename )
@ -950,6 +968,19 @@ function RANGE:SetTargetSheet( path, prefix )
return self return self
end end
--- Set FunkMan socket. Bombing and strafing results will be send to your Discord bot.
-- **Requires running FunkMan program**.
-- @param #RANGE self
-- @param #number Port Port. Default `10042`.
-- @param #string Host Host. Default "127.0.0.1".
-- @return #RANGE self
function RANGE:SetFunkManOn(Port, Host)
self.funkmanSocket=SOCKET:New(Port, Host)
return self
end
--- Set messages to examiner. The examiner will receive messages from all clients. --- Set messages to examiner. The examiner will receive messages from all clients.
-- @param #RANGE self -- @param #RANGE self
-- @param #string examinergroupname Name of the group of the examiner. -- @param #string examinergroupname Name of the group of the examiner.
@ -1728,7 +1759,6 @@ function RANGE:OnEventHit( EventData )
self:_DisplayMessageToGroup( _unit, text ) self:_DisplayMessageToGroup( _unit, text )
self:T2( self.id .. text ) self:T2( self.id .. text )
_currentTarget.pastfoulline = true _currentTarget.pastfoulline = true
invalidStrafe = true -- Rangeboss Edit
end end
end end
@ -1760,6 +1790,13 @@ function RANGE:OnEventHit( EventData )
end end
end end
--- Range event handler for event shot (when a unit releases a rocket or bomb (but not a fast firing gun).
-- @param #RANGE self
-- @param #table weapon Weapon
function RANGE:_TrackWeapon(weapon)
end
--- Range event handler for event shot (when a unit releases a rocket or bomb (but not a fast firing gun). --- Range event handler for event shot (when a unit releases a rocket or bomb (but not a fast firing gun).
-- @param #RANGE self -- @param #RANGE self
-- @param Core.Event#EVENTDATA EventData -- @param Core.Event#EVENTDATA EventData
@ -1807,6 +1844,11 @@ function RANGE:OnEventShot( EventData )
-- Get player unit and name. -- Get player unit and name.
local _unit, _playername = self:_GetPlayerUnitAndName( _unitName ) local _unit, _playername = self:_GetPlayerUnitAndName( _unitName )
-- Attack parameters.
local attackHdg=_unit:GetHeading()
local attackAlt=_unit:GetHeight()
local attackVel=_unit:GetVelocityKNOTS()
-- Set this to larger value than the threshold. -- Set this to larger value than the threshold.
local dPR = self.BombtrackThreshold * 2 local dPR = self.BombtrackThreshold * 2
@ -1848,7 +1890,6 @@ function RANGE:OnEventShot( EventData )
-- Check again in ~0.005 seconds ==> 200 checks per second. -- Check again in ~0.005 seconds ==> 200 checks per second.
return timer.getTime() + self.dtBombtrack return timer.getTime() + self.dtBombtrack
else else
----------------------------- -----------------------------
@ -1858,7 +1899,7 @@ function RANGE:OnEventShot( EventData )
-- Get closet target to last position. -- Get closet target to last position.
local _closetTarget = nil -- #RANGE.BombTarget local _closetTarget = nil -- #RANGE.BombTarget
local _distance = nil local _distance = nil
local _closeCoord = nil local _closeCoord = nil --Core.Point#COORDINATE
local _hitquality = "POOR" local _hitquality = "POOR"
-- Get callsign. -- Get callsign.
@ -1886,6 +1927,7 @@ function RANGE:OnEventShot( EventData )
-- Loop over defined bombing targets. -- Loop over defined bombing targets.
for _, _bombtarget in pairs( self.bombingTargets ) do for _, _bombtarget in pairs( self.bombingTargets ) do
local bombtarget=_bombtarget --#RANGE.BombTarget
-- Get target coordinate. -- Get target coordinate.
local targetcoord = self:_GetBombTargetCoordinate( _bombtarget ) local targetcoord = self:_GetBombTargetCoordinate( _bombtarget )
@ -1898,15 +1940,15 @@ function RANGE:OnEventShot( EventData )
-- Find closest target to last known position of the bomb. -- Find closest target to last known position of the bomb.
if _distance == nil or _temp < _distance then if _distance == nil or _temp < _distance then
_distance = _temp _distance = _temp
_closetTarget = _bombtarget _closetTarget = bombtarget
_closeCoord = targetcoord _closeCoord = targetcoord
if _distance <= 1.53 then -- Rangeboss Edit if _distance <= 1.53 then -- Rangeboss Edit
_hitquality = "SHACK" -- Rangeboss Edit _hitquality = "SHACK" -- Rangeboss Edit
elseif _distance <= 0.5 * _bombtarget.goodhitrange then -- Rangeboss Edit elseif _distance <= 0.5 * bombtarget.goodhitrange then -- Rangeboss Edit
_hitquality = "EXCELLENT" _hitquality = "EXCELLENT"
elseif _distance <= _bombtarget.goodhitrange then elseif _distance <= bombtarget.goodhitrange then
_hitquality = "GOOD" _hitquality = "GOOD"
elseif _distance <= 2 * _bombtarget.goodhitrange then elseif _distance <= 2 * bombtarget.goodhitrange then
_hitquality = "INEFFECTIVE" _hitquality = "INEFFECTIVE"
else else
_hitquality = "POOR" _hitquality = "POOR"
@ -1927,6 +1969,7 @@ function RANGE:OnEventShot( EventData )
local _results = self.bombPlayerResults[_playername] local _results = self.bombPlayerResults[_playername]
local result = {} -- #RANGE.BombResult local result = {} -- #RANGE.BombResult
result.command=SOCKET.DataType.BOMBRESULT
result.name = _closetTarget.name or "unknown" result.name = _closetTarget.name or "unknown"
result.distance = _distance result.distance = _distance
result.radial = _closeCoord:HeadingTo( impactcoord ) result.radial = _closeCoord:HeadingTo( impactcoord )
@ -1934,11 +1977,17 @@ function RANGE:OnEventShot( EventData )
result.quality = _hitquality result.quality = _hitquality
result.player = playerData.playername result.player = playerData.playername
result.time = timer.getAbsTime() result.time = timer.getAbsTime()
result.clock = UTILS.SecondsToClock(result.time, true)
result.midate = UTILS.GetDCSMissionDate()
result.theatre = env.mission.theatre
result.airframe = playerData.airframe result.airframe = playerData.airframe
result.roundsFired = 0 -- Rangeboss Edit result.roundsFired = 0 -- Rangeboss Edit
result.roundsHit = 0 -- Rangeboss Edit result.roundsHit = 0 -- Rangeboss Edit
result.roundsQuality = "N/A" -- Rangeboss Edit result.roundsQuality = "N/A" -- Rangeboss Edit
result.rangename = self.rangename result.rangename = self.rangename
result.attackHdg = attackHdg
result.attackVel = attackVel
result.attackAlt = attackAlt
-- Add to table. -- Add to table.
table.insert( _results, result ) table.insert( _results, result )
@ -2078,13 +2127,13 @@ function RANGE:onafterImpact( From, Event, To, result, player )
-- Only display target name if there is more than one bomb target. -- Only display target name if there is more than one bomb target.
local targetname = nil local targetname = nil
if #self.bombingTargets > 1 then if #self.bombingTargets > 1 then
local targetname = result.name targetname = result.name
end end
-- Send message to player. -- Send message to player.
local text = string.format( "%s, impact %03d° for %d ft", player.playername, result.radial, UTILS.MetersToFeet( result.distance ) ) local text = string.format( "%s, impact %03d° for %d ft", player.playername, result.radial, UTILS.MetersToFeet( result.distance ) )
if targetname then if targetname then
text = text .. string.format( " from bulls of target %s." ) text = text .. string.format( " from bulls of target %s.", targetname )
else else
text = text .. "." text = text .. "."
end end
@ -2110,17 +2159,41 @@ function RANGE:onafterImpact( From, Event, To, result, player )
end end
-- Unit. -- Unit.
if player.unitname then
-- Get unit.
local unit = UNIT:FindByName( player.unitname ) local unit = UNIT:FindByName( player.unitname )
-- Send message. -- Send message.
self:_DisplayMessageToGroup( unit, text, nil, true ) self:_DisplayMessageToGroup( unit, text, nil, true )
self:T( self.id .. text ) self:T( self.id .. text )
end
-- Save results. -- Save results.
if self.autosave then if self.autosave then
self:Save() self:Save()
end end
-- Send result to FunkMan, which creates fancy MatLab figures and sends them to Discord via a bot.
if self.funkmanSocket then
self.funkmanSocket:SendTable(result)
end
end
--- Function called after strafing run.
-- @param #RANGE self
-- @param #string From From state.
-- @param #string Event Event.
-- @param #string To To state.
-- @param #RANGE.PlayerData player Player data table.
-- @param #RANGE.StrafeResult result Result of run.
function RANGE:onafterStrafeResult( From, Event, To, player, result)
if self.funkmanSocket then
self.funkmanSocket:SendTable(result)
end
end end
--- Function called before save event. Checks that io and lfs are desanitized. --- Function called before save event. Checks that io and lfs are desanitized.
@ -2175,7 +2248,7 @@ function RANGE:onafterSave( From, Event, To )
local target = result.name local target = result.name
local radial = result.radial local radial = result.radial
local quality = result.quality local quality = result.quality
local time = UTILS.SecondsToClock( result.time ) local time = UTILS.SecondsToClock(result.time, true)
local airframe = result.airframe local airframe = result.airframe
local date = "n/a" local date = "n/a"
if os then if os then
@ -2353,7 +2426,8 @@ end
--- Start smoking a coordinate with a delay. --- Start smoking a coordinate with a delay.
-- @param #table _args Argements passed. -- @param #table _args Argements passed.
function RANGE._DelayedSmoke( _args ) function RANGE._DelayedSmoke( _args )
trigger.action.smoke( _args.coord:GetVec3(), _args.color ) _args.coord:Smoke(_args.color)
--trigger.action.smoke( _args.coord:GetVec3(), _args.color )
end end
--- Display top 10 stafing results of a specific player. --- Display top 10 stafing results of a specific player.
@ -3045,9 +3119,13 @@ function RANGE:_CheckInZone( _unitName )
-- Strafe result. -- Strafe result.
local result = {} -- #RANGE.StrafeResult local result = {} -- #RANGE.StrafeResult
result.command=SOCKET.DataType.STRAFERESULT
result.player=_playername result.player=_playername
result.name=_result.zone.name or "unknown" result.name=_result.zone.name or "unknown"
result.time = timer.getAbsTime() result.time = timer.getAbsTime()
result.clock = UTILS.SecondsToClock(result.time)
result.midate = UTILS.GetDCSMissionDate()
result.theatre = env.mission.theatre
result.roundsFired = shots result.roundsFired = shots
result.roundsHit = _result.hits result.roundsHit = _result.hits
result.roundsQuality = resulttext result.roundsQuality = resulttext
@ -3473,6 +3551,7 @@ function RANGE:_DisplayMessageToGroup( _unit, _text, _time, _clear, display )
-- Group ID. -- Group ID.
local _gid = _unit:GetGroup():GetID() local _gid = _unit:GetGroup():GetID()
local _grp = _unit:GetGroup()
-- Get playername and player settings -- Get playername and player settings
local _, playername = self:_GetPlayerUnitAndName( _unit:GetName() ) local _, playername = self:_GetPlayerUnitAndName( _unit:GetName() )
@ -3480,14 +3559,14 @@ function RANGE:_DisplayMessageToGroup( _unit, _text, _time, _clear, display )
-- Send message to player if messages enabled and not only for the examiner. -- Send message to player if messages enabled and not only for the examiner.
if _gid and (playermessage == true or display) and (not self.examinerexclusive) then if _gid and (playermessage == true or display) and (not self.examinerexclusive) then
trigger.action.outTextForGroup( _gid, _text, _time, _clear ) local m = MESSAGE:New(_text,_time,nil,_clear):ToUnit(_unit)
end end
-- Send message to examiner. -- Send message to examiner.
if self.examinergroupname ~= nil then if self.examinergroupname ~= nil then
local _examinerid = GROUP:FindByName( self.examinergroupname ):GetID() local _examinerid = GROUP:FindByName( self.examinergroupname )
if _examinerid then if _examinerid then
trigger.action.outTextForGroup( _examinerid, _text, _time, _clear ) local m = MESSAGE:New(_text,_time,nil,_clear):ToGroup(_examinerid)
end end
end end
end end

View File

@ -656,11 +656,12 @@ function SCORING:_AddPlayerFromUnit( UnitData )
if self.Players[PlayerName].UnitCoalition ~= UnitCoalition and self.penaltyoncoalitionchange then if self.Players[PlayerName].UnitCoalition ~= UnitCoalition and self.penaltyoncoalitionchange then
self.Players[PlayerName].Penalty = self.Players[PlayerName].Penalty + self.CoalitionChangePenalty or 50 self.Players[PlayerName].Penalty = self.Players[PlayerName].Penalty + self.CoalitionChangePenalty or 50
self.Players[PlayerName].PenaltyCoalition = self.Players[PlayerName].PenaltyCoalition + 1 self.Players[PlayerName].PenaltyCoalition = self.Players[PlayerName].PenaltyCoalition + 1
MESSAGE:NewType( self.DisplayMessagePrefix .. "Player '" .. PlayerName .. "' changed coalition from " .. _SCORINGCoalition[self.Players[PlayerName].UnitCoalition] .. " to " .. _SCORINGCoalition[UnitCoalition] .. "(changed " .. self.Players[PlayerName].PenaltyCoalition .. " times the coalition). " .. MESSAGE:NewType( self.DisplayMessagePrefix .. "Player '" .. PlayerName .. "' changed coalition from " .. _SCORINGCoalition[self.Players[PlayerName].UnitCoalition] .. " to " .. _SCORINGCoalition[UnitCoalition] ..
self.CoalitionChangePenalty .. "Penalty points added.", "(changed " .. self.Players[PlayerName].PenaltyCoalition .. " times the coalition). ".. self.CoalitionChangePenalty .."Penalty points added.",
MESSAGE.Type.Information ) MESSAGE.Type.Information
:ToAll() ):ToAll()
self:ScoreCSV( PlayerName, "", "COALITION_PENALTY", 1, -1 * self.CoalitionChangePenalty, self.Players[PlayerName].UnitName, _SCORINGCoalition[self.Players[PlayerName].UnitCoalition], _SCORINGCategory[self.Players[PlayerName].UnitCategory], self.Players[PlayerName].UnitType, UnitName, _SCORINGCoalition[UnitCoalition], _SCORINGCategory[UnitCategory], UnitData:GetTypeName() ) self:ScoreCSV( PlayerName, "", "COALITION_PENALTY", 1, -1*self.CoalitionChangePenalty, self.Players[PlayerName].UnitName, _SCORINGCoalition[self.Players[PlayerName].UnitCoalition], _SCORINGCategory[self.Players[PlayerName].UnitCategory], self.Players[PlayerName].UnitType,
UnitName, _SCORINGCoalition[UnitCoalition], _SCORINGCategory[UnitCategory], UnitData:GetTypeName() )
end end
end end
@ -1116,12 +1117,14 @@ function SCORING:_EventOnHit( Event )
PlayerHit.Penalty = PlayerHit.Penalty + 10 --* self.ScaleDestroyPenalty PlayerHit.Penalty = PlayerHit.Penalty + 10 --* self.ScaleDestroyPenalty
PlayerHit.PenaltyHit = PlayerHit.PenaltyHit + 1 * self.ScaleDestroyPenalty PlayerHit.PenaltyHit = PlayerHit.PenaltyHit + 1 * self.ScaleDestroyPenalty
MESSAGE:NewType( self.DisplayMessagePrefix .. "Player '" .. Event.WeaponPlayerName .. "' hit friendly target " .. TargetUnitCategory .. " ( " .. TargetType .. " ) " .. MESSAGE
:NewType( self.DisplayMessagePrefix .. "Player '" .. Event.WeaponPlayerName .. "' hit friendly target " ..
TargetUnitCategory .. " ( " .. TargetType .. " ) " ..
"Penalty: -" .. PlayerHit.Penalty .. " = " .. Player.Score - Player.Penalty, "Penalty: -" .. PlayerHit.Penalty .. " = " .. Player.Score - Player.Penalty,
MESSAGE.Type.Update ) MESSAGE.Type.Update
)
:ToAllIf( self:IfMessagesHit() and self:IfMessagesToAll() ) :ToAllIf( self:IfMessagesHit() and self:IfMessagesToAll() )
:ToCoalitionIf( Event.WeaponCoalition, self:IfMessagesHit() and self:IfMessagesToCoalition() ) :ToCoalitionIf( Event.WeaponCoalition, self:IfMessagesHit() and self:IfMessagesToCoalition() )
self:ScoreCSV( Event.WeaponPlayerName, TargetPlayerName, "HIT_PENALTY", 1, -10, Event.WeaponName, Event.WeaponCoalition, Event.WeaponCategory, Event.WeaponTypeName, TargetUnitName, TargetUnitCoalition, TargetUnitCategory, TargetUnitType ) self:ScoreCSV( Event.WeaponPlayerName, TargetPlayerName, "HIT_PENALTY", 1, -10, Event.WeaponName, Event.WeaponCoalition, Event.WeaponCategory, Event.WeaponTypeName, TargetUnitName, TargetUnitCoalition, TargetUnitCategory, TargetUnitType )
else else
Player.Score = Player.Score + 1 Player.Score = Player.Score + 1
@ -1652,7 +1655,8 @@ function SCORING:ReportScoreGroupDetailed( PlayerGroup )
local PlayerScore = ScoreHits + ScoreDestroys + ScoreCoalitionChanges + ScoreGoals + ScoreMissions local PlayerScore = ScoreHits + ScoreDestroys + ScoreCoalitionChanges + ScoreGoals + ScoreMissions
local PlayerPenalty = PenaltyHits + PenaltyDestroys + PenaltyCoalitionChanges + PenaltyGoals + PenaltyMissions local PlayerPenalty = PenaltyHits + PenaltyDestroys + PenaltyCoalitionChanges + PenaltyGoals + PenaltyMissions
PlayerMessage = string.format( "Player '%s' Score = %d ( %d Score, -%d Penalties )%s%s%s%s%s", PlayerMessage =
string.format( "Player '%s' Score = %d ( %d Score, -%d Penalties )%s%s%s%s%s",
PlayerName, PlayerName,
PlayerScore - PlayerPenalty, PlayerScore - PlayerPenalty,
PlayerScore, PlayerScore,
@ -1707,7 +1711,8 @@ function SCORING:ReportScoreAllSummary( PlayerGroup )
local PlayerScore = ScoreHits + ScoreDestroys + ScoreCoalitionChanges + ScoreGoals + ScoreMissions local PlayerScore = ScoreHits + ScoreDestroys + ScoreCoalitionChanges + ScoreGoals + ScoreMissions
local PlayerPenalty = PenaltyHits + PenaltyDestroys + PenaltyCoalitionChanges + PenaltyGoals + PenaltyMissions local PlayerPenalty = PenaltyHits + PenaltyDestroys + PenaltyCoalitionChanges + PenaltyGoals + PenaltyMissions
PlayerMessage = string.format( "Player '%s' Score = %d ( %d Score, -%d Penalties )", PlayerMessage =
string.format( "Player '%s' Score = %d ( %d Score, -%d Penalties )",
PlayerName, PlayerName,
PlayerScore - PlayerPenalty, PlayerScore - PlayerPenalty,
PlayerScore, PlayerScore,

View File

@ -79,6 +79,7 @@ SEAD = {
["Kh25"] = "Kh25", ["Kh25"] = "Kh25",
["BGM_109"] = "BGM_109", ["BGM_109"] = "BGM_109",
["AGM_154"] = "AGM_154", ["AGM_154"] = "AGM_154",
["HY-2"] = "HY-2",
} }
--- Missile enumerators - from DCS ME and Wikipedia --- Missile enumerators - from DCS ME and Wikipedia
@ -98,6 +99,7 @@ SEAD = {
["Kh25"] = {25, 0.8}, ["Kh25"] = {25, 0.8},
["BGM_109"] = {460, 0.705}, --in-game ~465kn ["BGM_109"] = {460, 0.705}, --in-game ~465kn
["AGM_154"] = {130, 0.61}, ["AGM_154"] = {130, 0.61},
["HY-2"] = {90,1},
} }
--- Creates the main object which is handling defensive actions for SA sites or moving SA vehicles. --- Creates the main object which is handling defensive actions for SA sites or moving SA vehicles.

View File

@ -18,7 +18,7 @@
-- @module Functional.Shorad -- @module Functional.Shorad
-- @image Functional.Shorad.jpg -- @image Functional.Shorad.jpg
-- --
-- Date: July 2021 -- Date: Nov 2021
------------------------------------------------------------------------- -------------------------------------------------------------------------
--- **SHORAD** class, extends Core.Base#BASE --- **SHORAD** class, extends Core.Base#BASE
@ -41,6 +41,7 @@
-- @field #boolean UseEmOnOff Decide if we are using Emission on/off (default) or AlarmState red/green. -- @field #boolean UseEmOnOff Decide if we are using Emission on/off (default) or AlarmState red/green.
-- @extends Core.Base#BASE -- @extends Core.Base#BASE
--- *Good friends are worth defending.* Mr Tushman, Wonder (the Movie) --- *Good friends are worth defending.* Mr Tushman, Wonder (the Movie)
-- --
-- Simple Class for a more intelligent Short Range Air Defense System -- Simple Class for a more intelligent Short Range Air Defense System
@ -131,6 +132,7 @@ do
["Kh29"] = "Kh29", ["Kh29"] = "Kh29",
["Kh31"] = "Kh31", ["Kh31"] = "Kh31",
["Kh66"] = "Kh66", ["Kh66"] = "Kh66",
--["BGM_109"] = "BGM_109",
} }
--- Instantiates a new SHORAD object --- Instantiates a new SHORAD object
@ -138,13 +140,13 @@ do
-- @param #string Name Name of this SHORAD -- @param #string Name Name of this SHORAD
-- @param #string ShoradPrefix Filter for the Shorad #SET_GROUP -- @param #string ShoradPrefix Filter for the Shorad #SET_GROUP
-- @param Core.Set#SET_GROUP Samset The #SET_GROUP of SAM sites to defend -- @param Core.Set#SET_GROUP Samset The #SET_GROUP of SAM sites to defend
-- @param #number Radius Defense radius in meters, used to switch on groups -- @param #number Radius Defense radius in meters, used to switch on SHORAD groups **within** this radius
-- @param #number ActiveTimer Determines how many seconds the systems stay on red alert after wake-up call -- @param #number ActiveTimer Determines how many seconds the systems stay on red alert after wake-up call
-- @param #string Coalition Coalition, i.e. "blue", "red", or "neutral" -- @param #string Coalition Coalition, i.e. "blue", "red", or "neutral"
-- @param #boolean UseEmOnOff Use Emissions On/Off rather than Alarm State Red/Green (default: use Emissions switch) -- @param #boolean UseEmOnOff Use Emissions On/Off rather than Alarm State Red/Green (default: use Emissions switch)
-- @retunr #SHORAD self -- @retunr #SHORAD self
function SHORAD:New(Name, ShoradPrefix, Samset, Radius, ActiveTimer, Coalition, UseEmOnOff) function SHORAD:New(Name, ShoradPrefix, Samset, Radius, ActiveTimer, Coalition, UseEmOnOff)
local self = BASE:Inherit( self, BASE:New() ) local self = BASE:Inherit( self, FSM:New() )
self:T({Name, ShoradPrefix, Samset, Radius, ActiveTimer, Coalition}) self:T({Name, ShoradPrefix, Samset, Radius, ActiveTimer, Coalition})
local GroupSet = SET_GROUP:New():FilterPrefixes(ShoradPrefix):FilterCoalitions(Coalition):FilterCategoryGround():FilterStart() local GroupSet = SET_GROUP:New():FilterPrefixes(ShoradPrefix):FilterCoalitions(Coalition):FilterCategoryGround():FilterStart()
@ -162,11 +164,17 @@ do
self.DefenseLowProb = 70 -- probability to detect a missile shot, low margin self.DefenseLowProb = 70 -- probability to detect a missile shot, low margin
self.DefenseHighProb = 90 -- probability to detect a missile shot, high margin self.DefenseHighProb = 90 -- probability to detect a missile shot, high margin
self.UseEmOnOff = UseEmOnOff or false -- Decide if we are using Emission on/off (default) or AlarmState red/green self.UseEmOnOff = UseEmOnOff or false -- Decide if we are using Emission on/off (default) or AlarmState red/green
self:I("*** SHORAD - Started Version 0.2.8") self:I("*** SHORAD - Started Version 0.3.1")
-- Set the string id for output to DCS.log file. -- Set the string id for output to DCS.log file.
self.lid=string.format("SHORAD %s | ", self.name) self.lid=string.format("SHORAD %s | ", self.name)
self:_InitState() self:_InitState()
self:HandleEvent(EVENTS.Shot, self.HandleEventShot) self:HandleEvent(EVENTS.Shot, self.HandleEventShot)
-- Start State.
self:SetStartState("Running")
self:AddTransition("*", "WakeUpShorad", "*")
self:AddTransition("*", "CalculateHitZone", "*")
return self return self
end end
@ -310,7 +318,7 @@ do
local hit = false local hit = false
if self.DefendHarms then if self.DefendHarms then
for _,_name in pairs (SHORAD.Harms) do for _,_name in pairs (SHORAD.Harms) do
if string.find(WeaponName,_name,1) then hit = true end if string.find(WeaponName,_name,1,true) then hit = true end
end end
end end
return hit return hit
@ -326,7 +334,7 @@ do
local hit = false local hit = false
if self.DefendMavs then if self.DefendMavs then
for _,_name in pairs (SHORAD.Mavs) do for _,_name in pairs (SHORAD.Mavs) do
if string.find(WeaponName,_name,1) then hit = true end if string.find(WeaponName,_name,1,true) then hit = true end
end end
end end
return hit return hit
@ -367,7 +375,7 @@ do
local returnname = false local returnname = false
for _,_groups in pairs (shoradset) do for _,_groups in pairs (shoradset) do
local groupname = _groups:GetName() local groupname = _groups:GetName()
if string.find(groupname, tgtgrp, 1) then if string.find(groupname, tgtgrp, 1, true) then
returnname = true returnname = true
--_groups:RelocateGroundRandomInRadius(7,100,false,false) -- be a bit evasive --_groups:RelocateGroundRandomInRadius(7,100,false,false) -- be a bit evasive
end end
@ -388,7 +396,7 @@ do
local returnname = false local returnname = false
for _,_groups in pairs (shoradset) do for _,_groups in pairs (shoradset) do
local groupname = _groups:GetName() local groupname = _groups:GetName()
if string.find(groupname, tgtgrp, 1) then if string.find(groupname, tgtgrp, 1, true) then
returnname = true returnname = true
end end
end end
@ -400,6 +408,7 @@ do
-- @return #boolean Returns true for a detection, else false -- @return #boolean Returns true for a detection, else false
function SHORAD:_ShotIsDetected() function SHORAD:_ShotIsDetected()
self:T(self.lid .. " _ShotIsDetected") self:T(self.lid .. " _ShotIsDetected")
if self.debug then return true end
local IsDetected = false local IsDetected = false
local DetectionProb = math.random(self.DefenseLowProb, self.DefenseHighProb) -- reference value local DetectionProb = math.random(self.DefenseLowProb, self.DefenseHighProb) -- reference value
local ActualDetection = math.random(1,100) -- value for this shot local ActualDetection = math.random(1,100) -- value for this shot
@ -423,7 +432,7 @@ do
-- mymantis = MANTIS:New("BlueMantis","Blue SAM","Blue EWR",nil,"blue",false,"Blue Awacs") -- mymantis = MANTIS:New("BlueMantis","Blue SAM","Blue EWR",nil,"blue",false,"Blue Awacs")
-- mymantis:AddShorad(myshorad,720) -- mymantis:AddShorad(myshorad,720)
-- mymantis:Start() -- mymantis:Start()
function SHORAD:WakeUpShorad(TargetGroup, Radius, ActiveTimer, TargetCat) function SHORAD:onafterWakeUpShorad(From, Event, To, TargetGroup, Radius, ActiveTimer, TargetCat)
self:T(self.lid .. " WakeUpShorad") self:T(self.lid .. " WakeUpShorad")
self:T({TargetGroup, Radius, ActiveTimer, TargetCat}) self:T({TargetGroup, Radius, ActiveTimer, TargetCat})
local targetcat = TargetCat or Object.Category.UNIT local targetcat = TargetCat or Object.Category.UNIT
@ -477,6 +486,76 @@ do
return self return self
end end
--- (Internal) Calculate hit zone of an AGM-88
-- @param #SHORAD self
-- @param #table SEADWeapon DCS.Weapon object
-- @param Core.Point#COORDINATE pos0 Position of the plane when it fired
-- @param #number height Height when the missile was fired
-- @param Wrapper.Group#GROUP SEADGroup Attacker group
-- @return #SHORAD self
function SHORAD:onafterCalculateHitZone(From,Event,To,SEADWeapon,pos0,height,SEADGroup)
self:T("**** Calculating hit zone")
if SEADWeapon and SEADWeapon:isExist() then
--local pos = SEADWeapon:getPoint()
-- postion and height
local position = SEADWeapon:getPosition()
local mheight = height
-- heading
local wph = math.atan2(position.x.z, position.x.x)
if wph < 0 then
wph=wph+2*math.pi
end
wph=math.deg(wph)
-- velocity
local wpndata = SEAD.HarmData["AGM_88"]
local mveloc = math.floor(wpndata[2] * 340.29)
local c1 = (2*mheight*9.81)/(mveloc^2)
local c2 = (mveloc^2) / 9.81
local Ropt = c2 * math.sqrt(c1+1)
if height <= 5000 then
Ropt = Ropt * 0.72
elseif height <= 7500 then
Ropt = Ropt * 0.82
elseif height <= 10000 then
Ropt = Ropt * 0.87
elseif height <= 12500 then
Ropt = Ropt * 0.98
end
-- look at a couple of zones across the trajectory
for n=1,3 do
local dist = Ropt - ((n-1)*20000)
local predpos= pos0:Translate(dist,wph)
if predpos then
local targetzone = ZONE_RADIUS:New("Target Zone",predpos:GetVec2(),20000)
if self.debug then
predpos:MarkToAll(string.format("height=%dm | heading=%d | velocity=%ddeg | Ropt=%dm",mheight,wph,mveloc,Ropt),false)
targetzone:DrawZone(coalition.side.BLUE,{0,0,1},0.2,nil,nil,3,true)
end
local seadset = self.Groupset
local tgtcoord = targetzone:GetRandomPointVec2()
local tgtgrp = seadset:FindNearestGroupFromPointVec2(tgtcoord)
local _targetgroup = nil
local _targetgroupname = "none"
local _targetskill = "Random"
if tgtgrp and tgtgrp:IsAlive() then
_targetgroup = tgtgrp
_targetgroupname = tgtgrp:GetName() -- group name
_targetskill = tgtgrp:GetUnit(1):GetSkill()
self:T("*** Found Target = ".. _targetgroupname)
self:WakeUpShorad(_targetgroupname, self.Radius, self.ActiveTimer, Object.Category.UNIT)
end
end
end
end
return self
end
--- Main function - work on the EventData --- Main function - work on the EventData
-- @param #SHORAD self -- @param #SHORAD self
-- @param Core.Event#EVENTDATA EventData The event details table data set -- @param Core.Event#EVENTDATA EventData The event details table data set
@ -504,13 +583,48 @@ do
if (self:_CheckHarms(ShootingWeaponName) or self:_CheckMavs(ShootingWeaponName)) and IsDetected then if (self:_CheckHarms(ShootingWeaponName) or self:_CheckMavs(ShootingWeaponName)) and IsDetected then
-- get target data -- get target data
local targetdata = EventData.Weapon:getTarget() -- Identify target local targetdata = EventData.Weapon:getTarget() -- Identify target
-- Is there target data?
if not targetdata or self.debug then
if string.find(ShootingWeaponName,"AGM_88",1,true) then
self:I("**** Tracking AGM-88 with no target data.")
local pos0 = EventData.IniUnit:GetCoordinate()
local fheight = EventData.IniUnit:GetHeight()
self:__CalculateHitZone(20,ShootingWeapon,pos0,fheight,EventData.IniGroup)
end
return self
end
local targetcat = targetdata:getCategory() -- Identify category local targetcat = targetdata:getCategory() -- Identify category
self:T(string.format("Target Category (3=STATIC, 1=UNIT)= %s",tostring(targetcat))) self:T(string.format("Target Category (3=STATIC, 1=UNIT)= %s",tostring(targetcat)))
self:T({targetdata})
local targetunit = nil local targetunit = nil
if targetcat == Object.Category.UNIT then -- UNIT if targetcat == Object.Category.UNIT then -- UNIT
targetunit = UNIT:Find(targetdata) targetunit = UNIT:Find(targetdata)
elseif targetcat == Object.Category.STATIC then -- STATIC elseif targetcat == Object.Category.STATIC then -- STATIC
targetunit = STATIC:Find(targetdata) --self:T("Static Target Data")
--self:T({targetdata:isExist()})
--self:T({targetdata:getPoint()})
local tgtcoord = COORDINATE:NewFromVec3(targetdata:getPoint())
--tgtcoord:MarkToAll("Missile Target",true)
local tgtgrp1 = self.Samset:FindNearestGroupFromPointVec2(tgtcoord)
local tgtcoord1 = tgtgrp1:GetCoordinate()
--tgtcoord1:MarkToAll("Close target SAM",true)
local tgtgrp2 = self.Groupset:FindNearestGroupFromPointVec2(tgtcoord)
local tgtcoord2 = tgtgrp2:GetCoordinate()
--tgtcoord2:MarkToAll("Close target SHORAD",true)
local dist1 = tgtcoord:Get2DDistance(tgtcoord1)
local dist2 = tgtcoord:Get2DDistance(tgtcoord2)
if dist1 < dist2 then
targetunit = tgtgrp1
targetcat = Object.Category.UNIT
else
targetunit = tgtgrp2
targetcat = Object.Category.UNIT
end
end end
--local targetunitname = Unit.getName(targetdata) -- Unit name --local targetunitname = Unit.getName(targetdata) -- Unit name
if targetunit and targetunit:IsAlive() then if targetunit and targetunit:IsAlive() then
@ -519,7 +633,11 @@ do
local targetgroup = nil local targetgroup = nil
local targetgroupname = "none" local targetgroupname = "none"
if targetcat == Object.Category.UNIT then if targetcat == Object.Category.UNIT then
if targetunit.ClassName == "UNIT" then
targetgroup = targetunit:GetGroup() targetgroup = targetunit:GetGroup()
elseif targetunit.ClassName == "GROUP" then
targetgroup = targetunit
end
targetgroupname = targetgroup:GetName() -- group name targetgroupname = targetgroup:GetName() -- group name
elseif targetcat == Object.Category.STATIC then elseif targetcat == Object.Category.STATIC then
targetgroup = targetunit targetgroup = targetunit
@ -540,6 +658,7 @@ do
end end
end end
end end
return self
end end
-- --
end end

File diff suppressed because it is too large Load Diff

View File

@ -174,6 +174,7 @@ RADIOSPEECH.Vocabulary.RU = {
["br"] = { "br", 1.1 }, ["br"] = { "br", 1.1 },
["bra"] = { "bra", 0.3 }, ["bra"] = { "bra", 0.3 },
["возвращение на базу"] = { "returning_to_base", 1.40 }, ["возвращение на базу"] = { "returning_to_base", 1.40 },
["на пути к наземной цели"] = { "on_route_to_ground_target", 1.45 }, ["на пути к наземной цели"] = { "on_route_to_ground_target", 1.45 },
["перехват боги"] = { "intercepting_bogeys", 1.22 }, ["перехват боги"] = { "intercepting_bogeys", 1.22 },

View File

@ -1098,3 +1098,5 @@ end
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------

View File

@ -144,7 +144,7 @@ do -- UserSound
-- @return #USERSOUND The usersound instance. -- @return #USERSOUND The usersound instance.
-- @usage -- @usage
-- local BlueVictory = USERSOUND:New( "BlueVictory.ogg" ) -- local BlueVictory = USERSOUND:New( "BlueVictory.ogg" )
-- local PlayerUnit = UNIT:FindByName( "PlayerUnit" ) -- Search for the active group named "PlayerUnit", a human player. -- local PlayerUnit = UNIT:FindByName( "PlayerUnit" ) -- Search for the active unit named "PlayerUnit", a human player.
-- BlueVictory:ToUnit( PlayerUnit ) -- Play the victory sound to the player unit. -- BlueVictory:ToUnit( PlayerUnit ) -- Play the victory sound to the player unit.
-- --
function USERSOUND:ToUnit( Unit, Delay ) function USERSOUND:ToUnit( Unit, Delay )

View File

@ -20,11 +20,11 @@ do
-- @type FIFO -- @type FIFO
-- @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 #string version Version of FiFo -- @field #string version Version of FiFo.
-- @field #number counter -- @field #number counter Counter.
-- @field #number pointer -- @field #number pointer Pointer.
-- @field #table stackbypointer -- @field #table stackbypointer Stack by pointer.
-- @field #table stackbyid -- @field #table stackbyid Stack by ID.
-- @extends Core.Base#BASE -- @extends Core.Base#BASE
--- ---
@ -45,12 +45,12 @@ FIFO = {
stackbyid = {} stackbyid = {}
} }
--- Instantiate a new FIFO Stack --- Instantiate a new FIFO Stack.
-- @param #FIFO self -- @param #FIFO self
-- @return #FIFO self -- @return #FIFO self
function FIFO:New() function FIFO:New()
-- Inherit everything from BASE class. -- Inherit everything from BASE class.
local self=BASE:Inherit(self, BASE:New()) local self=BASE:Inherit(self, BASE:New()) --#FIFO
self.pointer = 0 self.pointer = 0
self.counter = 0 self.counter = 0
self.stackbypointer = {} self.stackbypointer = {}
@ -62,7 +62,7 @@ function FIFO:New()
return self return self
end end
--- Empty FIFO Stack --- Empty FIFO Stack.
-- @param #FIFO self -- @param #FIFO self
-- @return #FIFO self -- @return #FIFO self
function FIFO:Clear() function FIFO:Clear()
@ -77,7 +77,7 @@ function FIFO:Clear()
return self return self
end end
--- FIFO Push Object to Stack --- FIFO Push Object to Stack.
-- @param #FIFO self -- @param #FIFO self
-- @param #table Object -- @param #table Object
-- @param #string UniqueID (optional) - will default to current pointer + 1. Note - if you intend to use `FIFO:GetIDStackSorted()` keep the UniqueID numerical! -- @param #string UniqueID (optional) - will default to current pointer + 1. Note - if you intend to use `FIFO:GetIDStackSorted()` keep the UniqueID numerical!
@ -97,7 +97,7 @@ function FIFO:Push(Object,UniqueID)
return self return self
end end
--- FIFO Pull Object from Stack --- FIFO Pull Object from Stack.
-- @param #FIFO self -- @param #FIFO self
-- @return #table Object or nil if stack is empty -- @return #table Object or nil if stack is empty
function FIFO:Pull() function FIFO:Pull()

View File

@ -7,7 +7,7 @@
-- ### Author: **TAW CougarNL**, *funkyfranky* -- ### Author: **TAW CougarNL**, *funkyfranky*
-- --
-- @module Utilities.PROFILER -- @module Utilities.PROFILER
-- @image MOOSE.JPG -- @image Utils_Profiler.jpg
--- PROFILER class. --- PROFILER class.
-- @type PROFILER -- @type PROFILER
@ -24,7 +24,8 @@
-- @field #number ThreshTtot Total time threshold. Only write output if total function CPU time is more than this value. -- @field #number ThreshTtot Total time threshold. Only write output if total function CPU time is more than this value.
-- @field #string fileNamePrefix Output file name prefix, e.g. "MooseProfiler". -- @field #string fileNamePrefix Output file name prefix, e.g. "MooseProfiler".
-- @field #string fileNameSuffix Output file name prefix, e.g. "txt" -- @field #string fileNameSuffix Output file name prefix, e.g. "txt"
--- *The emperor counsels simplicity. First principles. Of each particular thing, ask: What is it in itself, in its own constitution? What is its causal nature? *
--- *The emperor counsels simplicity.* *First principles. Of each particular thing, ask: What is it in itself, in its own constitution? What is its causal nature?*
-- --
-- === -- ===
-- --
@ -33,11 +34,24 @@
-- # The PROFILER Concept -- # The PROFILER Concept
-- --
-- Profile your lua code. This tells you, which functions are called very often and which consume most real time. -- Profile your lua code. This tells you, which functions are called very often and which consume most real time.
-- With this information you can optimize the performance of your code. -- With this information you can optimize the perfomance of your code.
-- --
-- # Prerequisites -- # Prerequisites
-- --
-- The modules **os** and **lfs** need to be de-sanitized. -- The modules **os**, **io** and **lfs** need to be desanizied. Comment out the lines
--
-- --sanitizeModule('os')
-- --sanitizeModule('io')
-- --sanitizeModule('lfs')
--
-- in your *"DCS World OpenBeta/Scripts/MissionScripting.lua"* file.
--
-- But be aware that these changes can make you system vulnerable to attacks.
--
-- # Disclaimer
--
-- **Profiling itself is CPU expensive!** Don't use this when you want to fly or host a mission.
--
-- --
-- # Start -- # Start
-- --
@ -123,11 +137,11 @@ function PROFILER.Start( Delay, Duration )
go = false go = false
end end
if not io then if not io then
env.error( "ERROR: Profiler needs io to be de-sanitized!" ) env.error("ERROR: Profiler needs io to be desanitized!")
go=false go=false
end end
if not lfs then if not lfs then
env.error( "ERROR: Profiler needs lfs to be de-sanitized!" ) env.error("ERROR: Profiler needs lfs to be desanitized!")
go=false go=false
end end
if not go then if not go then
@ -158,6 +172,7 @@ function PROFILER.Start( Delay, Duration )
env.info(string.format("- Output file \"%s\" in CSV format", PROFILER.getfilename("csv"))) env.info(string.format("- Output file \"%s\" in CSV format", PROFILER.getfilename("csv")))
env.info('###############################################################################') env.info('###############################################################################')
-- Message on screen -- Message on screen
local duration=Duration or 600 local duration=Duration or 600
trigger.action.outText("### Profiler running ###", duration) trigger.action.outText("### Profiler running ###", duration)
@ -176,6 +191,14 @@ end
--- Stop profiler. --- Stop profiler.
-- @param #number Delay Delay before stop in seconds. -- @param #number Delay Delay before stop in seconds.
function PROFILER.Stop( Delay )
if Delay and Delay > 0 then
BASE:ScheduleOnce( Delay, PROFILER.Stop )
end
end
function PROFILER.Stop(Delay) function PROFILER.Stop(Delay)
if Delay and Delay>0 then if Delay and Delay>0 then
@ -187,6 +210,7 @@ function PROFILER.Stop( Delay )
-- Remove hook. -- Remove hook.
debug.sethook() debug.sethook()
-- Run time game. -- Run time game.
local runTimeGame=timer.getTime()-PROFILER.TstartGame local runTimeGame=timer.getTime()-PROFILER.TstartGame
@ -379,20 +403,25 @@ function PROFILER.showInfo( runTimeGame, runTimeOS )
local tforgen=nil --#PROFILER.Data local tforgen=nil --#PROFILER.Data
local tpairs=nil --#PROFILER.Data local tpairs=nil --#PROFILER.Data
for func, count in pairs(PROFILER.Counters) do for func, count in pairs(PROFILER.Counters) do
local s,src,line,tm=PROFILER.getData(func) local s,src,line,tm=PROFILER.getData(func)
if PROFILER.logUnknown==true then if PROFILER.logUnknown==true then
if s == nil then if s==nil then s="<Unknown>" end
s = "<Unknown>"
end
end end
if s~=nil then if s~=nil then
-- Profile data. -- Profile data.
local T = { func = s, src = src, line = line, count = count, tm = tm } -- #PROFILER.Data local T=
{ func=s,
src=src,
line=line,
count=count,
tm=tm,
} --#PROFILER.Data
-- Collect special cases. Somehow, e.g. "_copy" appears multiple times so we try to gather all data. -- Collect special cases. Somehow, e.g. "_copy" appears multiple times so we try to gather all data.
if s == "_copy" then if s == "_copy" then
@ -462,9 +491,7 @@ function PROFILER.showInfo( runTimeGame, runTimeOS )
env.info("##############################################################################") env.info("##############################################################################")
-- Sort by total time. -- Sort by total time.
table.sort( t, function( a, b ) table.sort(t, function(a,b) return a.tm>b.tm end)
return a.tm > b.tm
end )
-- Write data. -- Write data.
PROFILER._flog(f,"") PROFILER._flog(f,"")
@ -491,9 +518,7 @@ function PROFILER.showInfo( runTimeGame, runTimeOS )
PROFILER.showTable(t, f, runTimeGame) PROFILER.showTable(t, f, runTimeGame)
-- Sort by number of calls. -- Sort by number of calls.
table.sort( t, function( a, b ) table.sort(t, function(a,b) return a.tm/a.count>b.tm/b.count end)
return a.tm / a.count > b.tm / b.count
end )
-- Detailed data. -- Detailed data.
PROFILER._flog(f,"") PROFILER._flog(f,"")
@ -506,9 +531,7 @@ function PROFILER.showInfo( runTimeGame, runTimeOS )
PROFILER.showTable(t, f, runTimeGame) PROFILER.showTable(t, f, runTimeGame)
-- Sort by number of calls. -- Sort by number of calls.
table.sort( t, function( a, b ) table.sort(t, function(a,b) return a.count>b.count end)
return a.count > b.count
end )
-- Detailed data. -- Detailed data.
PROFILER._flog(f,"") PROFILER._flog(f,"")

View File

@ -546,7 +546,9 @@ routines.ground.buildWP = function( point, overRideForm, overRideSpeed )
end end
wp.type = 'Turning Point' wp.type = 'Turning Point'
return wp return wp
end end
routines.fixedWing.buildWP = function(point, WPtype, speed, alt, altType) routines.fixedWing.buildWP = function(point, WPtype, speed, alt, altType)
@ -677,6 +679,7 @@ routines.groupToRandomPoint = function( vars )
local headingDegrees = vars.headingDegrees local headingDegrees = vars.headingDegrees
local speed = vars.speed or routines.utils.kmphToMps(20) local speed = vars.speed or routines.utils.kmphToMps(20)
local useRoads local useRoads
if not vars.disableRoads then if not vars.disableRoads then
useRoads = true useRoads = true
@ -703,6 +706,7 @@ routines.groupToRandomPoint = function( vars )
offset.z = routines.utils.round(math.cos(heading + (math.pi/2)) * 50 + rndCoord.y, 3) offset.z = routines.utils.round(math.cos(heading + (math.pi/2)) * 50 + rndCoord.y, 3)
path[#path + 1] = routines.ground.buildWP(posStart, form, speed) path[#path + 1] = routines.ground.buildWP(posStart, form, speed)
if useRoads == true and ((point.x - posStart.x)^2 + (point.z - posStart.z)^2)^0.5 > radius * 1.3 then if useRoads == true and ((point.x - posStart.x)^2 + (point.z - posStart.z)^2)^0.5 > radius * 1.3 then
path[#path + 1] = routines.ground.buildWP({['x'] = posStart.x + 11, ['z'] = posStart.z + 11}, 'off_road', speed) path[#path + 1] = routines.ground.buildWP({['x'] = posStart.x + 11, ['z'] = posStart.z + 11}, 'off_road', speed)
path[#path + 1] = routines.ground.buildWP(posStart, 'on_road', speed) path[#path + 1] = routines.ground.buildWP(posStart, 'on_road', speed)
@ -715,14 +719,18 @@ routines.groupToRandomPoint = function( vars )
path[#path + 1] = routines.ground.buildWP(rndCoord, form, speed) path[#path + 1] = routines.ground.buildWP(rndCoord, form, speed)
routines.goRoute(group, path) routines.goRoute(group, path)
return
end end
routines.groupRandomDistSelf = function(gpData, dist, form, heading, speed) routines.groupRandomDistSelf = function(gpData, dist, form, heading, speed)
local pos = routines.getLeadPos(gpData) local pos = routines.getLeadPos(gpData)
local fakeZone = {} local fakeZone = {}
fakeZone.radius = dist or math.random(300, 1000) fakeZone.radius = dist or math.random(300, 1000)
fakeZone.point = { x = pos.x, y, pos.y, z = pos.z } fakeZone.point = {x = pos.x, y = pos.y, z = pos.z}
routines.groupToRandomZone(gpData, fakeZone, form, heading, speed) routines.groupToRandomZone(gpData, fakeZone, form, heading, speed)
return
end end
routines.groupToRandomZone = function(gpData, zone, form, heading, speed) routines.groupToRandomZone = function(gpData, zone, form, heading, speed)
@ -749,6 +757,8 @@ routines.groupToRandomZone = function( gpData, zone, form, heading, speed )
vars.point = routines.utils.zoneToVec3(zone) vars.point = routines.utils.zoneToVec3(zone)
routines.groupToRandomPoint(vars) routines.groupToRandomPoint(vars)
return
end end
routines.isTerrainValid = function(coord, terrainTypes) -- vec2/3 and enum or table of acceptable terrain types routines.isTerrainValid = function(coord, terrainTypes) -- vec2/3 and enum or table of acceptable terrain types
@ -796,8 +806,11 @@ routines.groupToPoint = function( gpData, point, form, heading, speed, useRoads
vars.disableRoads = useRoads vars.disableRoads = useRoads
vars.point = routines.utils.zoneToVec3(point) vars.point = routines.utils.zoneToVec3(point)
routines.groupToRandomPoint(vars) routines.groupToRandomPoint(vars)
return
end end
routines.getLeadPos = function(group) routines.getLeadPos = function(group)
if type(group) == 'string' then -- group name if type(group) == 'string' then -- group name
group = Group.getByName(group) group = Group.getByName(group)

View File

@ -127,6 +127,9 @@ end
-- --
-- * (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min -- * (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min
-- --
-- @param #number length can also be passed as #string
-- @param #number speed Defaults to 1.0
-- @param #boolean isGoogle We're using Google TTS
function STTS.getSpeechTime(length,speed,isGoogle) function STTS.getSpeechTime(length,speed,isGoogle)
local maxRateRatio = 3 local maxRateRatio = 3
@ -153,7 +156,7 @@ function STTS.getSpeechTime( length, speed, isGoogle )
length = string.len( length ) length = string.len( length )
end end
return math.ceil( length / cps ) return length/cps --math.ceil(length/cps)
end end
--- Text to speech function. --- Text to speech function.

View File

@ -0,0 +1,152 @@
--- **Utilities** - Socket.
--
-- **Main Features:**
--
-- * Creates UDP Sockets
-- * Send messages to Discord
-- * Compatible with [FunkMan](https://github.com/funkyfranky/FunkMan)
-- * Compatible with [DCSServerBot](https://github.com/Special-K-s-Flightsim-Bots/DCSServerBot)
--
-- ===
--
-- ### Author: **funkyfranky**
-- @module Utilities.Socket
-- @image Utilities_Socket.png
--- SOCKET class.
-- @type SOCKET
-- @field #string ClassName Name of the class.
-- @field #number verbose Verbosity level.
-- @field #string lid Class id string for output to DCS log file.
-- @field #table socket The socket.
-- @field #number port The port.
-- @field #string host The host.
-- @field #table json JSON.
-- @extends Core.Fsm#FSM
--- **At times I feel like a socket that remembers its tooth.** -- Saul Bellow
--
-- ===
--
-- # The SOCKET Concept
--
-- Create a UDP socket server. It enables you to send messages to discord servers via discord bots.
--
-- **Note** that you have to **de-sanitize** `require` and `package` in your `MissionScripting.lua` file, which is in your `DCS/Scripts` folder.
--
--
-- @field #SOCKET
SOCKET = {
ClassName = "SOCKET",
verbose = 0,
lid = nil,
}
--- Data type. This is the keyword the socket listener uses.
-- @field #string TEXT Plain text.
-- @field #string BOMBRESULT Range bombing.
-- @field #string STRAFERESULT Range strafeing result.
-- @field #string LSOGRADE Airboss LSO grade.
SOCKET.DataType={
TEXT="moose_text",
BOMBRESULT="moose_bomb_result",
STRAFERESULT="moose_strafe_result",
LSOGRADE="moose_lso_grade",
}
--- SOCKET class version.
-- @field #string version
SOCKET.version="0.1.0"
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO list
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO: A lot!
-- TODO: Messages as spoiler.
-- TODO: Send images?
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Constructor
-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Create a new SOCKET object.
-- @param #SOCKET self
-- @param #number Port UDP port. Default `10042`.
-- @param #string Host Host. Default `"127.0.0.1"`.
-- @return #SOCKET self
function SOCKET:New(Port, Host)
-- Inherit everything from FSM class.
local self=BASE:Inherit(self, FSM:New()) --#SOCKET
package.path = package.path..";.\\LuaSocket\\?.lua;"
package.cpath = package.cpath..";.\\LuaSocket\\?.dll;"
self.socket = require("socket")
self.port=Port or 10042
self.host=Host or "127.0.0.1"
self.json=loadfile("Scripts\\JSON.lua")()
self.UDPSendSocket=self.socket.udp()
self.UDPSendSocket:settimeout(0)
return self
end
--- Set port.
-- @param #SOCKET self
-- @param #number Port Port. Default 10042.
-- @return #SOCKET self
function SOCKET:SetPort(Port)
self.port=Port or 10042
end
--- Set host.
-- @param #SOCKET self
-- @param #string Host Host. Default `"127.0.0.1"`.
-- @return #SOCKET self
function SOCKET:SetHost(Host)
self.host=Host or "127.0.0.1"
end
--- Send a table.
-- @param #SOCKET self
-- @param #table Table Table to send.
-- @return #SOCKET self
function SOCKET:SendTable(Table)
local json= self.json:encode(Table)
-- Debug info.
self:T("Json table:")
self:T(json)
-- Send data.
self.socket.try(self.UDPSendSocket:sendto(json, self.host, self.port))
return self
end
--- Send a text message.
-- @param #SOCKET self
-- @param #string Text Test message.
-- @return #SOCKET self
function SOCKET:SendText(Text)
local message={}
message.command = SOCKET.DataType.TEXT
message.text = Text
self:SendTable(message)
return self
end

View File

@ -1155,7 +1155,7 @@ function UTILS.VecHdg(a)
end end
--- Calculate "heading" of a 2D vector in the X-Y plane. --- Calculate "heading" of a 2D vector in the X-Y plane.
-- @param DCS#Vec2 a Vector in "D with x, y components. -- @param DCS#Vec2 a Vector in 2D with x, y components.
-- @return #number Heading in degrees in [0,360). -- @return #number Heading in degrees in [0,360).
function UTILS.Vec2Hdg(a) function UTILS.Vec2Hdg(a)
local h=math.deg(math.atan2(a.y, a.x)) local h=math.deg(math.atan2(a.y, a.x))

View File

@ -11,6 +11,7 @@
-- @module Wrapper.Airbase -- @module Wrapper.Airbase
-- @image Wrapper_Airbase.JPG -- @image Wrapper_Airbase.JPG
--- @type AIRBASE --- @type AIRBASE
-- @field #string ClassName Name of the class, i.e. "AIRBASE". -- @field #string ClassName Name of the class, i.e. "AIRBASE".
-- @field #table CategoryName Names of airbase categories. -- @field #table CategoryName Names of airbase categories.
@ -24,9 +25,11 @@
-- @field #boolean isShip Airbase is a ship. -- @field #boolean isShip Airbase is a ship.
-- @field #table parking Parking spot data. -- @field #table parking Parking spot data.
-- @field #table parkingByID Parking spot data table with ID as key. -- @field #table parkingByID Parking spot data table with ID as key.
-- @field #number activerwyno Active runway number (forced).
-- @field #table parkingWhitelist List of parking spot terminal IDs considered for spawning. -- @field #table parkingWhitelist List of parking spot terminal IDs considered for spawning.
-- @field #table parkingBlacklist List of parking spot terminal IDs **not** considered for spawning. -- @field #table parkingBlacklist List of parking spot terminal IDs **not** considered for spawning.
-- @field #table runways Runways of airdromes.
-- @field #AIRBASE.Runway runwayLanding Runway used for landing.
-- @field #AIRBASE.Runway runwayTakeoff Runway used for takeoff.
-- @extends Wrapper.Positionable#POSITIONABLE -- @extends Wrapper.Positionable#POSITIONABLE
--- Wrapper class to handle the DCS Airbase objects: --- Wrapper class to handle the DCS Airbase objects:
@ -519,7 +522,6 @@ AIRBASE.SouthAtlantic={
["El_Calafate"]="El Calafate", ["El_Calafate"]="El Calafate",
} }
--- AIRBASE.ParkingSpot ".Coordinate, ".TerminalID", ".TerminalType", ".TOAC", ".Free", ".TerminalID0", ".DistToRwy". --- AIRBASE.ParkingSpot ".Coordinate, ".TerminalID", ".TerminalType", ".TOAC", ".Free", ".TerminalID0", ".DistToRwy".
-- @type AIRBASE.ParkingSpot -- @type AIRBASE.ParkingSpot
-- @field Core.Point#COORDINATE Coordinate Coordinate of the parking spot. -- @field Core.Point#COORDINATE Coordinate Coordinate of the parking spot.
@ -529,6 +531,14 @@ AIRBASE.SouthAtlantic={
-- @field #boolean Free This spot is currently free, i.e. there is no alive aircraft on it at the present moment. -- @field #boolean Free This spot is currently free, i.e. there is no alive aircraft on it at the present moment.
-- @field #number TerminalID0 Unknown what this means. If you know, please tell us! -- @field #number TerminalID0 Unknown what this means. If you know, please tell us!
-- @field #number DistToRwy Distance to runway in meters. Currently bugged and giving the same number as the TerminalID. -- @field #number DistToRwy Distance to runway in meters. Currently bugged and giving the same number as the TerminalID.
-- @field #string AirbaseName Name of the airbase.
-- @field #number MarkerID Numerical ID of marker placed at parking spot.
-- @field Wrapper.Marker#MARKER Marker The marker on the F10 map.
-- @field #string ClientSpot If `true`, this is a parking spot of a client aircraft.
-- @field #string ClientName Client unit name of this spot.
-- @field #string Status Status of spot e.g. `AIRBASE.SpotStatus.FREE`.
-- @field #string OccupiedBy Name of the aircraft occupying the spot or "unknown". Can be *nil* if spot is not occupied.
-- @field #string ReservedBy Name of the aircraft for which this spot is reserved. Can be *nil* if spot is not reserved.
--- Terminal Types of parking spots. See also https://wiki.hoggitworld.com/view/DCS_func_getParking --- Terminal Types of parking spots. See also https://wiki.hoggitworld.com/view/DCS_func_getParking
-- --
@ -563,13 +573,30 @@ AIRBASE.TerminalType = {
FighterAircraft=244, FighterAircraft=244,
} }
--- Status of a parking spot.
-- @type AIRBASE.SpotStatus
-- @field #string FREE Spot is free.
-- @field #string OCCUPIED Spot is occupied.
-- @field #string RESERVED Spot is reserved.
AIRBASE.SpotStatus = {
FREE="Free",
OCCUPIED="Occupied",
RESERVED="Reserved",
}
--- Runway data. --- Runway data.
-- @type AIRBASE.Runway -- @type AIRBASE.Runway
-- @field #number heading Heading of the runway in degrees. -- @field #string name Runway name.
-- @field #string idx Runway ID: heading 070° ==> idx="07". -- @field #string idx Runway ID: heading 070° ==> idx="07".
-- @field #number heading True heading of the runway in degrees.
-- @field #number magheading Magnetic heading of the runway in degrees. This is what is marked on the runway.
-- @field #number length Length of runway in meters. -- @field #number length Length of runway in meters.
-- @field #number width Width of runway in meters.
-- @field Core.Zone#ZONE_POLYGON zone Runway zone.
-- @field Core.Point#COORDINATE center Center of the runway.
-- @field Core.Point#COORDINATE position Position of runway start. -- @field Core.Point#COORDINATE position Position of runway start.
-- @field Core.Point#COORDINATE endpoint End point of runway. -- @field Core.Point#COORDINATE endpoint End point of runway.
-- @field #boolean isLeft If `true`, this is the left of two parallel runways. If `false`, this is the right of two runways. If `nil`, no parallel runway exists.
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- Registration -- Registration
@ -593,6 +620,9 @@ function AIRBASE:Register( AirbaseName )
-- Get descriptors. -- Get descriptors.
self.descriptors=self:GetDesc() self.descriptors=self:GetDesc()
-- Debug info.
--self:I({airbase=AirbaseName, descriptors=self.descriptors})
-- Category. -- Category.
self.category=self.descriptors and self.descriptors.category or Airbase.Category.AIRDROME self.category=self.descriptors and self.descriptors.category or Airbase.Category.AIRDROME
@ -614,8 +644,18 @@ function AIRBASE:Register( AirbaseName )
self:E("ERROR: Unknown airbase category!") self:E("ERROR: Unknown airbase category!")
end end
-- Init Runways.
self:_InitRunways()
-- Set the active runways based on wind direction.
if self.isAirdrome then
self:SetActiveRunway()
end
-- Init parking spots.
self:_InitParkingSpots() self:_InitParkingSpots()
-- Get 2D position vector.
local vec2=self:GetVec2() local vec2=self:GetVec2()
-- Init coordinate. -- Init coordinate.
@ -828,6 +868,43 @@ function AIRBASE:SetParkingSpotBlacklist( TerminalIdBlacklist )
return self return self
end end
--- Sets the ATC belonging to an airbase object to be silent and unresponsive. This is useful for disabling the award winning ATC behavior in DCS.
-- Note that this DOES NOT remove the airbase from the list. It just makes it unresponsive and silent to any radio calls to it.
-- @param #AIRBASE self
-- @param #boolean Silent If `true`, enable silent mode. If `false` or `nil`, disable silent mode.
-- @return #AIRBASE self
function AIRBASE:SetRadioSilentMode(Silent)
-- Get DCS airbase object.
local airbase=self:GetDCSObject()
-- Set mode.
if airbase then
airbase:setRadioSilentMode(Silent)
end
return self
end
--- Check whether or not the airbase has been silenced.
-- @param #AIRBASE self
-- @return #boolean If `true`, silent mode is enabled.
function AIRBASE:GetRadioSilentMode()
-- Is silent?
local silent=nil
-- Get DCS airbase object.
local airbase=self:GetDCSObject()
-- Set mode.
if airbase then
silent=airbase:getRadioSilentMode()
end
return silent
end
--- Get category of airbase. --- Get category of airbase.
-- @param #AIRBASE self -- @param #AIRBASE self
-- @return #number Category of airbase from GetDesc().category. -- @return #number Category of airbase from GetDesc().category.
@ -1008,6 +1085,21 @@ function AIRBASE:_InitParkingSpots()
self.NparkingTerminal[terminalType]=0 self.NparkingTerminal[terminalType]=0
end end
-- Get client coordinates.
local function isClient(coord)
local clients=_DATABASE.CLIENTS
for clientname, _client in pairs(clients) do
local client=_client --Wrapper.Client#CLIENT
if client and client.SpawnCoord then
local dist=client.SpawnCoord:Get2DDistance(coord)
if dist<2 then
return true, clientname
end
end
end
return false, nil
end
-- Put coordinates of parking spots into table. -- Put coordinates of parking spots into table.
for _,spot in pairs(parkingdata) do for _,spot in pairs(parkingdata) do
@ -1021,6 +1113,8 @@ function AIRBASE:_InitParkingSpots()
park.TerminalID0=spot.Term_Index_0 park.TerminalID0=spot.Term_Index_0
park.TerminalType=spot.Term_Type park.TerminalType=spot.Term_Type
park.TOAC=spot.TO_AC park.TOAC=spot.TO_AC
park.ClientSpot, park.ClientName=isClient(park.Coordinate)
park.AirbaseName=self.AirbaseName
self.NparkingTotal=self.NparkingTotal+1 self.NparkingTotal=self.NparkingTotal+1
@ -1079,6 +1173,7 @@ function AIRBASE:GetParkingSpotsTable( termtype )
spot.Free=_isfree(_spot) -- updated spot.Free=_isfree(_spot) -- updated
spot.TOAC=_spot.TO_AC -- updated spot.TOAC=_spot.TO_AC -- updated
spot.AirbaseName=self.AirbaseName
table.insert(spots, spot) table.insert(spots, spot)
@ -1115,6 +1210,7 @@ function AIRBASE:GetFreeParkingSpotsTable( termtype, allowTOAC )
spot.Free=true -- updated spot.Free=true -- updated
spot.TOAC=_spot.TO_AC -- updated spot.TOAC=_spot.TO_AC -- updated
spot.AirbaseName=self.AirbaseName
table.insert(freespots, spot) table.insert(freespots, spot)
@ -1167,7 +1263,8 @@ function AIRBASE:MarkParkingSpots( termtype, mark )
for _,_spot in pairs(parkingdata) do for _,_spot in pairs(parkingdata) do
-- Mark text. -- Mark text.
local _text = string.format( "Term Index=%d, Term Type=%d, Free=%s, TOAC=%s, Term ID0=%d, Dist2Rwy=%.1f m", _spot.TerminalID, _spot.TerminalType, tostring( _spot.Free ), tostring( _spot.TOAC ), _spot.TerminalID0, _spot.DistToRwy ) local _text=string.format("Term Index=%d, Term Type=%d, Free=%s, TOAC=%s, Term ID0=%d, Dist2Rwy=%.1f m",
_spot.TerminalID, _spot.TerminalType,tostring(_spot.Free),tostring(_spot.TOAC),_spot.TerminalID0,_spot.DistToRwy)
-- Create mark on the F10 map. -- Create mark on the F10 map.
if mark then if mark then
@ -1175,7 +1272,8 @@ function AIRBASE:MarkParkingSpots( termtype, mark )
end end
-- Info to DCS.log file. -- Info to DCS.log file.
local _text = string.format( "%s, Term Index=%3d, Term Type=%03d, Free=%5s, TOAC=%5s, Term ID0=%3d, Dist2Rwy=%.1f m", airbasename, _spot.TerminalID, _spot.TerminalType, tostring( _spot.Free ), tostring( _spot.TOAC ), _spot.TerminalID0, _spot.DistToRwy ) local _text=string.format("%s, Term Index=%3d, Term Type=%03d, Free=%5s, TOAC=%5s, Term ID0=%3d, Dist2Rwy=%.1f m",
airbasename, _spot.TerminalID, _spot.TerminalType,tostring(_spot.Free),tostring(_spot.TOAC),_spot.TerminalID0,_spot.DistToRwy)
self:E(_text) self:E(_text)
end end
end end
@ -1250,6 +1348,7 @@ function AIRBASE:FindFreeParkingSpotForAircraft( group, terminaltype, scanradius
az = 17 -- width az = 17 -- width
end end
-- Number of spots we are looking for. Note that, e.g. grouping can require a number different from the group size! -- Number of spots we are looking for. Note that, e.g. grouping can require a number different from the group size!
local _nspots=nspots or group:GetSize() local _nspots=nspots or group:GetSize()
@ -1396,6 +1495,7 @@ function AIRBASE:_CheckParkingLists( TerminalID )
end end
end end
-- Check if a whitelist was defined. -- Check if a whitelist was defined.
if self.parkingWhitelist and #self.parkingWhitelist>0 then if self.parkingWhitelist and #self.parkingWhitelist>0 then
for _,terminalID in pairs(self.parkingWhitelist or {}) do for _,terminalID in pairs(self.parkingWhitelist or {}) do
@ -1462,6 +1562,231 @@ end
-- Runway -- Runway
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
--- Get runways.
-- @param #AIRBASE self
-- @return #table Runway data.
function AIRBASE:GetRunways()
return self.runways or {}
end
--- Get runway by its name.
-- @param #AIRBASE self
-- @param #string Name Name of the runway, e.g. "31" or "21L".
-- @return #AIRBASE.Runway Runway data.
function AIRBASE:GetRunwayByName(Name)
if Name==nil then
return
end
if Name then
for _,_runway in pairs(self.runways) do
local runway=_runway --#AIRBASE.Runway
-- Name including L or R, e.g. "31L".
local name=self:GetRunwayName(runway)
if name==Name:upper() then
return runway
end
end
end
self:E("ERROR: Could not find runway with name "..tostring(Name))
return nil
end
--- Init runways.
-- @param #AIRBASE self
-- @param #boolean IncludeInverse If `true` or `nil`, include inverse runways.
-- @return #table Runway data.
function AIRBASE:_InitRunways(IncludeInverse)
-- Default is true.
if IncludeInverse==nil then
IncludeInverse=true
end
-- Runway table.
local Runways={}
if self:GetAirbaseCategory()~=Airbase.Category.AIRDROME then
self.runways={}
return {}
end
--- Function to create a runway data table.
local function _createRunway(name, course, width, length, center)
-- Bearing in rad.
local bearing=-1*course
-- Heading in degrees.
local heading=math.deg(bearing)
-- Data table.
local runway={} --#AIRBASE.Runway
runway.name=string.format("%02d", tonumber(name))
runway.magheading=tonumber(runway.name)*10
runway.heading=heading
runway.width=width or 0
runway.length=length or 0
runway.center=COORDINATE:NewFromVec3(center)
-- Ensure heading is [0,360]
if runway.heading>360 then
runway.heading=runway.heading-360
elseif runway.heading<0 then
runway.heading=runway.heading+360
end
-- For example at Nellis, DCS reports two runways, i.e. 03 and 21, BUT the "course" of both is -0.700 rad = 40 deg!
-- As a workaround, I check the difference between the "magnetic" heading derived from the name and the true heading.
-- If this is too large then very likely the "inverse" heading is the one we are looking for.
if math.abs(runway.heading-runway.magheading)>60 then
self:T(string.format("WARNING: Runway %s: heading=%.1f magheading=%.1f", runway.name, runway.heading, runway.magheading))
runway.heading=runway.heading-180
end
-- Ensure heading is [0,360]
if runway.heading>360 then
runway.heading=runway.heading-360
elseif runway.heading<0 then
runway.heading=runway.heading+360
end
-- Start and endpoint of runway.
runway.position=runway.center:Translate(-runway.length/2, runway.heading)
runway.endpoint=runway.center:Translate( runway.length/2, runway.heading)
local init=runway.center:GetVec3()
local width = runway.width/2
local L2=runway.length/2
local offset1 = {x = init.x + (math.cos(bearing + math.pi) * L2), y = init.z + (math.sin(bearing + math.pi) * L2)}
local offset2 = {x = init.x - (math.cos(bearing + math.pi) * L2), y = init.z - (math.sin(bearing + math.pi) * L2)}
local points={}
points[1] = {x = offset1.x + (math.cos(bearing + (math.pi/2)) * width), y = offset1.y + (math.sin(bearing + (math.pi/2)) * width)}
points[2] = {x = offset1.x + (math.cos(bearing - (math.pi/2)) * width), y = offset1.y + (math.sin(bearing - (math.pi/2)) * width)}
points[3] = {x = offset2.x + (math.cos(bearing - (math.pi/2)) * width), y = offset2.y + (math.sin(bearing - (math.pi/2)) * width)}
points[4] = {x = offset2.x + (math.cos(bearing + (math.pi/2)) * width), y = offset2.y + (math.sin(bearing + (math.pi/2)) * width)}
-- Runway zone.
runway.zone=ZONE_POLYGON_BASE:New(string.format("%s Runway %s", self.AirbaseName, runway.name), points)
return runway
end
-- Get DCS object.
local airbase=self:GetDCSObject()
if airbase then
-- Get DCS runways.
local runways=airbase:getRunways()
-- Debug info.
self:T2(runways)
if runways then
-- Loop over runways.
for _,rwy in pairs(runways) do
-- Debug info.
self:T(rwy)
-- Get runway data.
local runway=_createRunway(rwy.Name, rwy.course, rwy.width, rwy.length, rwy.position) --#AIRBASE.Runway
-- Add to table.
table.insert(Runways, runway)
-- Include "inverse" runway.
if IncludeInverse then
-- Create "inverse".
local idx=tonumber(runway.name)
local name2=tostring(idx-18)
if idx<18 then
name2=tostring(idx+18)
end
-- Create "inverse" runway.
local runway=_createRunway(name2, rwy.course-math.pi, rwy.width, rwy.length, rwy.position) --#AIRBASE.Runway
-- Add inverse to table.
table.insert(Runways, runway)
end
end
end
end
-- Look for identical (parallel) runways, e.g. 03L and 03R at Nellis.
local rpairs={}
for i,_ri in pairs(Runways) do
local ri=_ri --#AIRBASE.Runway
for j,_rj in pairs(Runways) do
local rj=_rj --#AIRBASE.Runway
if i<j then
if ri.name==rj.name then
rpairs[i]=j
end
end
end
end
local function isLeft(a, b, c)
--return ((b.x - a.x)*(c.z - a.z) - (b.z - a.z)*(c.x - a.x)) > 0
return ((b.z - a.z)*(c.x - a.x) - (b.x - a.x)*(c.z - a.z)) > 0
end
for i,j in pairs(rpairs) do
local ri=Runways[i] --#AIRBASE.Runway
local rj=Runways[j] --#AIRBASE.Runway
-- Draw arrow.
--ri.center:ArrowToAll(rj.center)
local c0=ri.center
-- Vector in the direction of the runway.
local a=UTILS.VecTranslate(c0, 1000, ri.heading)
-- Vector from runway i to runway j.
local b=UTILS.VecSubstract(rj.center, ri.center)
b=UTILS.VecAdd(ri.center, b)
-- Check if rj is left of ri.
local left=isLeft(c0, a, b)
--env.info(string.format("Found pair %s: i=%d, j=%d, left==%s", ri.name, i, j, tostring(left)))
if left then
ri.isLeft=false
rj.isLeft=true
else
ri.isLeft=true
rj.isLeft=false
end
--break
end
-- Set runways.
self.runways=Runways
return Runways
end
--- Get runways data. Only for airdromes! --- Get runways data. Only for airdromes!
-- @param #AIRBASE self -- @param #AIRBASE self
-- @param #number magvar (Optional) Magnetic variation in degrees. -- @param #number magvar (Optional) Magnetic variation in degrees.
@ -1498,6 +1823,7 @@ function AIRBASE:GetRunwayData( magvar, mark )
-- Airbase name. -- Airbase name.
local name=self:GetName() local name=self:GetName()
-- Exceptions -- Exceptions
if name==AIRBASE.Nevada.Jean_Airport or if name==AIRBASE.Nevada.Jean_Airport or
name==AIRBASE.Nevada.Creech_AFB or name==AIRBASE.Nevada.Creech_AFB or
@ -1585,6 +1911,7 @@ function AIRBASE:GetRunwayData( magvar, mark )
return j return j
end end
for i=1,N do for i=1,N do
-- Get the other spawn point coordinate. -- Get the other spawn point coordinate.
@ -1627,26 +1954,100 @@ function AIRBASE:GetRunwayData( magvar, mark )
return runways return runways
end end
--- Set the active runway in case it cannot be determined by the wind direction. --- Set the active runway for landing and takeoff.
-- @param #AIRBASE self -- @param #AIRBASE self
-- @param #number iactive Number of the active runway in the runway data table. -- @param #string Name Name of the runway, e.g. "31" or "02L" or "90R". If not given, the runway is determined from the wind direction.
function AIRBASE:SetActiveRunway( iactive ) -- @param #boolean PreferLeft If `true`, perfer the left runway. If `false`, prefer the right runway. If `nil` (default), do not care about left or right.
self.activerwyno = iactive function AIRBASE:SetActiveRunway(Name, PreferLeft)
self:SetActiveRunwayTakeoff(Name, PreferLeft)
self:SetActiveRunwayLanding(Name,PreferLeft)
end end
--- Get the active runway based on current wind direction. --- Set the active runway for landing.
-- @param #AIRBASE self -- @param #AIRBASE self
-- @param #number magvar (Optional) Magnetic variation in degrees. -- @param #string Name Name of the runway, e.g. "31" or "02L" or "90R". If not given, the runway is determined from the wind direction.
-- @param #boolean PreferLeft If `true`, perfer the left runway. If `false`, prefer the right runway. If `nil` (default), do not care about left or right.
-- @return #AIRBASE.Runway The active runway for landing.
function AIRBASE:SetActiveRunwayLanding(Name, PreferLeft)
local runway=self:GetRunwayByName(Name)
if not runway then
runway=self:GetRunwayIntoWind(PreferLeft)
end
if runway then
self:I(string.format("%s: Setting active runway for landing as %s", self.AirbaseName, self:GetRunwayName(runway)))
else
self:E("ERROR: Could not set the runway for landing!")
end
self.runwayLanding=runway
return runway
end
--- Get the active runways.
-- @param #AIRBASE self
-- @return #AIRBASE.Runway The active runway for landing.
-- @return #AIRBASE.Runway The active runway for takeoff.
function AIRBASE:GetActiveRunway()
return self.runwayLanding, self.runwayTakeoff
end
--- Get the active runway for landing.
-- @param #AIRBASE self
-- @return #AIRBASE.Runway The active runway for landing.
function AIRBASE:GetActiveRunwayLanding()
return self.runwayLanding
end
--- Get the active runway for takeoff.
-- @param #AIRBASE self
-- @return #AIRBASE.Runway The active runway for takeoff.
function AIRBASE:GetActiveRunwayTakeoff()
return self.runwayTakeoff
end
--- Set the active runway for takeoff.
-- @param #AIRBASE self
-- @param #string Name Name of the runway, e.g. "31" or "02L" or "90R". If not given, the runway is determined from the wind direction.
-- @param #boolean PreferLeft If `true`, perfer the left runway. If `false`, prefer the right runway. If `nil` (default), do not care about left or right.
-- @return #AIRBASE.Runway The active runway for landing.
function AIRBASE:SetActiveRunwayTakeoff(Name, PreferLeft)
local runway=self:GetRunwayByName(Name)
if not runway then
runway=self:GetRunwayIntoWind(PreferLeft)
end
if runway then
self:I(string.format("%s: Setting active runway for takeoff as %s", self.AirbaseName, self:GetRunwayName(runway)))
else
self:E("ERROR: Could not set the runway for takeoff!")
end
self.runwayTakeoff=runway
return runway
end
--- Get the runway where aircraft would be taking of or landing into the direction of the wind.
-- NOTE that this requires the wind to be non-zero as set in the mission editor.
-- @param #AIRBASE self
-- @param #boolean PreferLeft If `true`, perfer the left runway. If `false`, prefer the right runway. If `nil` (default), do not care about left or right.
-- @return #AIRBASE.Runway Active runway data table. -- @return #AIRBASE.Runway Active runway data table.
function AIRBASE:GetActiveRunway( magvar ) function AIRBASE:GetRunwayIntoWind(PreferLeft)
-- Get runways data (initialize if necessary). -- Get runway data.
local runways = self:GetRunwayData( magvar ) local runways=self:GetRunways()
-- Return user forced active runway if it was set.
if self.activerwyno then
return runways[self.activerwyno]
end
-- Get wind vector. -- Get wind vector.
local Vwind=self:GetCoordinate():GetWindWithTurbulenceVec3() local Vwind=self:GetCoordinate():GetWindWithTurbulenceVec3()
@ -1668,6 +2069,8 @@ function AIRBASE:GetActiveRunway( magvar )
for i,_runway in pairs(runways) do for i,_runway in pairs(runways) do
local runway=_runway --#AIRBASE.Runway local runway=_runway --#AIRBASE.Runway
if PreferLeft==nil or PreferLeft==runway.isLeft then
-- Angle in rad. -- Angle in rad.
local alpha=math.rad(runway.heading) local alpha=math.rad(runway.heading)
@ -1677,9 +2080,6 @@ function AIRBASE:GetActiveRunway( magvar )
-- Dot product: parallel component of the two vectors. -- Dot product: parallel component of the two vectors.
local dot=UTILS.VecDot(Vwind, Vrunway) local dot=UTILS.VecDot(Vwind, Vrunway)
-- Debug.
-- env.info(string.format("runway=%03d° dot=%.3f", runway.heading, dot))
-- New min? -- New min?
if dotmin==nil or dot<dotmin then if dotmin==nil or dot<dotmin then
dotmin=dot dotmin=dot
@ -1687,13 +2087,45 @@ function AIRBASE:GetActiveRunway( magvar )
end end
end end
end
else else
self:E( "WARNING: Norm of wind is zero! Cannot determine active runway based on wind direction." ) self:E("WARNING: Norm of wind is zero! Cannot determine runway based on wind direction")
end end
return runways[iact] return runways[iact]
end end
--- Get name of a given runway, e.g. "31L".
-- @param #AIRBASE self
-- @param #AIRBASE.Runway Runway The runway. Default is the active runway.
-- @param #boolean LongLeftRight If `true`, return "Left" or "Right" instead of "L" or "R".
-- @return #string Name of the runway or "XX" if it could not be found.
function AIRBASE:GetRunwayName(Runway, LongLeftRight)
Runway=Runway or self:GetActiveRunway()
local name="XX"
if Runway then
name=Runway.name
if Runway.isLeft==true then
if LongLeftRight then
name=name.." Left"
else
name=name.."L"
end
elseif Runway.isLeft==false then
if LongLeftRight then
name=name.." Right"
else
name=name.."R"
end
end
end
return name
end
--- Function that checks if at leat one unit of a group has been spawned close to a spawn point on the runway. --- Function that checks if at leat one unit of a group has been spawned close to a spawn point on the runway.
-- @param #AIRBASE self -- @param #AIRBASE self
-- @param Wrapper.Group#GROUP group Group to be checked. -- @param Wrapper.Group#GROUP group Group to be checked.

View File

@ -13,6 +13,17 @@
--- The CLIENT class --- The CLIENT class
-- @type CLIENT -- @type CLIENT
-- @field #string ClassName Name of the class.
-- @field #string ClientName Name of the client.
-- @field #string ClientBriefing Briefing.
-- @field #function ClientCallBack Callback function.
-- @field #table ClientParameters Parameters of the callback function.
-- @field #number ClientGroupID Group ID of the client.
-- @field #string ClientGroupName Group name.
-- @field #boolean ClientAlive Client alive.
-- @field #boolean ClientAlive2 Client alive 2.
-- @field #table Players Player table.
-- @field Core.Point#COORDINATE SpawnCoord Spawn coordinate from the template.
-- @extends Wrapper.Unit#UNIT -- @extends Wrapper.Unit#UNIT

View File

@ -671,7 +671,7 @@ end
--- Activate ICLS system of the CONTROLLABLE. The controllable should be an aircraft carrier! --- Activate ICLS system of the CONTROLLABLE. The controllable should be an aircraft carrier!
-- @param #CONTROLLABLE self -- @param #CONTROLLABLE self
-- @param #number Channel ICLS channel. -- @param #number Channel ICLS channel.
-- @param #number UnitID The ID of the unit the ICLS system is attached to. Useful if more units are in one group. -- @param #number UnitID The DCS UNIT ID of the unit the ICLS system is attached to. Useful if more units are in one group.
-- @param #string Callsign Morse code identification callsign. -- @param #string Callsign Morse code identification callsign.
-- @param #number Delay (Optional) Delay in seconds before the ICLS is deactivated. -- @param #number Delay (Optional) Delay in seconds before the ICLS is deactivated.
-- @return #CONTROLLABLE self -- @return #CONTROLLABLE self
@ -725,6 +725,34 @@ function CONTROLLABLE:CommandActivateLink4(Frequency, UnitID, Callsign, Delay)
return self return self
end end
--- Activate LINK4 system of the CONTROLLABLE. The controllable should be an aircraft carrier!
-- @param #CONTROLLABLE self
-- @param #number Frequency Link4 Frequency in MHz, e.g. 336
-- @param #number UnitID The DCS UNIT ID of the unit the LINK4 system is attached to. Useful if more units are in one group.
-- @param #string Callsign Morse code identification callsign.
-- @param #number Delay (Optional) Delay in seconds before the LINK4 is deactivated.
-- @return #CONTROLLABLE self
function CONTROLLABLE:CommandActivateLink4(Frequency, UnitID, Callsign, Delay)
-- Command to activate Link4 system.
local CommandActivateLink4= {
id = "ActivateLink4",
params= {
["frequency "] = Frequency*1000,
["unitId"] = UnitID,
["name"] = Callsign,
}
}
if Delay and Delay>0 then
SCHEDULER:New(nil, self.CommandActivateLink4, {self}, Delay)
else
self:SetCommand(CommandActivateLink4)
end
return self
end
--- Deactivate the active beacon of the CONTROLLABLE. --- Deactivate the active beacon of the CONTROLLABLE.
-- @param #CONTROLLABLE self -- @param #CONTROLLABLE self
-- @param #number Delay (Optional) Delay in seconds before the beacon is deactivated. -- @param #number Delay (Optional) Delay in seconds before the beacon is deactivated.
@ -734,6 +762,8 @@ function CONTROLLABLE:CommandDeactivateBeacon( Delay )
-- Command to deactivate -- Command to deactivate
local CommandDeactivateBeacon = { id = 'DeactivateBeacon', params = {} } local CommandDeactivateBeacon = { id = 'DeactivateBeacon', params = {} }
local CommandDeactivateBeacon={id='DeactivateBeacon', params={}}
if Delay and Delay>0 then if Delay and Delay>0 then
SCHEDULER:New(nil, self.CommandDeactivateBeacon, {self}, Delay) SCHEDULER:New(nil, self.CommandDeactivateBeacon, {self}, Delay)
else else
@ -743,6 +773,24 @@ function CONTROLLABLE:CommandDeactivateBeacon( Delay )
return self return self
end end
--- Deactivate the active Link4 of the CONTROLLABLE.
-- @param #CONTROLLABLE self
-- @param #number Delay (Optional) Delay in seconds before the Link4 is deactivated.
-- @return #CONTROLLABLE self
function CONTROLLABLE:CommandDeactivateLink4(Delay)
-- Command to deactivate
local CommandDeactivateLink4={id='DeactivateLink4', params={}}
if Delay and Delay>0 then
SCHEDULER:New(nil, self.CommandDeactivateLink4, {self}, Delay)
else
self:SetCommand(CommandDeactivateLink4)
end
return self
end
--- Deactivate the ICLS of the CONTROLLABLE. --- Deactivate the ICLS of the CONTROLLABLE.
-- @param #CONTROLLABLE self -- @param #CONTROLLABLE self
-- @param #number Delay (Optional) Delay in seconds before the ICLS is deactivated. -- @param #number Delay (Optional) Delay in seconds before the ICLS is deactivated.
@ -1424,7 +1472,7 @@ function CONTROLLABLE:TaskEscort( FollowControllable, Vec3, LastWaypointIndex, E
DCSTask = { DCSTask = {
id = 'Escort', id = 'Escort',
params = { params = {
groupId = FollowControllable:GetID(), groupId = FollowControllable and FollowControllable:GetID() or nil,
pos = Vec3, pos = Vec3,
lastWptIndexFlag = LastWaypointIndex and true or false, lastWptIndexFlag = LastWaypointIndex and true or false,
lastWptIndex = LastWaypointIndex, lastWptIndex = LastWaypointIndex,
@ -1457,7 +1505,7 @@ function CONTROLLABLE:TaskFireAtPoint( Vec2, Radius, AmmoCount, WeaponType, Alti
y = Vec2.y, y = Vec2.y,
zoneRadius = Radius, zoneRadius = Radius,
radius = Radius, radius = Radius,
expendQty = 100, -- dummy value expendQty = 1, -- dummy value
expendQtyEnabled = false, expendQtyEnabled = false,
alt_type = ASL and 0 or 1, alt_type = ASL and 0 or 1,
}, },
@ -1476,7 +1524,8 @@ function CONTROLLABLE:TaskFireAtPoint( Vec2, Radius, AmmoCount, WeaponType, Alti
DCSTask.params.weaponType = WeaponType DCSTask.params.weaponType = WeaponType
end end
-- self:I(DCSTask) --env.info("FF fireatpoint")
--BASE:I(DCSTask)
return DCSTask return DCSTask
end end
@ -1569,6 +1618,28 @@ function CONTROLLABLE:EnRouteTaskEngageTargetsInZone( Vec2, Radius, TargetTypes,
return DCSTask return DCSTask
end end
--- (AIR) Enroute anti-ship task.
-- @param #CONTROLLABLE self
-- @param DCS#AttributeNameArray TargetTypes Array of target categories allowed to engage. Default `{"Ships"}`.
-- @param #number Priority (Optional) All en-route tasks have the priority parameter. This is a number (less value - higher priority) that determines actions related to what task will be performed first. Default 0.
-- @return DCS#Task The DCS task structure.
function CONTROLLABLE:EnRouteTaskAntiShip(TargetTypes, Priority)
local DCSTask = {
id = 'EngageTargets',
key = "AntiShip",
--auto = false,
--enabled = true,
params = {
targetTypes = TargetTypes or {"Ships"},
priority = Priority or 0
}
}
return DCSTask
end
--- (AIR) Engaging a controllable. The task does not assign the target controllable to the unit/controllable to attack now; it just allows the unit/controllable to engage the target controllable as well as other assigned targets. --- (AIR) Engaging a controllable. The task does not assign the target controllable to the unit/controllable to attack now; it just allows the unit/controllable to engage the target controllable as well as other assigned targets.
-- @param #CONTROLLABLE self -- @param #CONTROLLABLE self
-- @param Wrapper.Controllable#CONTROLLABLE AttackGroup The Controllable to be attacked. -- @param Wrapper.Controllable#CONTROLLABLE AttackGroup The Controllable to be attacked.
@ -1835,7 +1906,7 @@ end
do -- Patrol methods do -- Patrol methods
--- (GROUND) Patrol iteratively using the waypoints the for the (parent) group. --- (GROUND) Patrol iteratively using the waypoints of the (parent) group.
-- @param #CONTROLLABLE self -- @param #CONTROLLABLE self
-- @return #CONTROLLABLE -- @return #CONTROLLABLE
function CONTROLLABLE:PatrolRoute() function CONTROLLABLE:PatrolRoute()
@ -1866,6 +1937,7 @@ do -- Patrol methods
end end
end end
local Waypoint = Waypoints[1] local Waypoint = Waypoints[1]
local Speed = Waypoint.speed or (20 / 3.6) local Speed = Waypoint.speed or (20 / 3.6)
local From = FromCoord:WaypointGround( Speed ) local From = FromCoord:WaypointGround( Speed )
@ -2023,22 +2095,21 @@ do -- Patrol methods
end end
--- Return a Mission task to follow a given route defined by Points.
--- Return a "Misson" task to follow a given route defined by Points.
-- @param #CONTROLLABLE self -- @param #CONTROLLABLE self
-- @param #table Points A table of route points. -- @param #table Points A table of route points.
-- @return DCS#Task -- @return DCS#Task DCS mission task. Has entries `.id="Mission"`, `params`, were params has entries `airborne` and `route`, which is a table of `points`.
function CONTROLLABLE:TaskRoute( Points ) function CONTROLLABLE:TaskRoute( Points )
self:F2( Points )
local DCSTask = { local DCSTask = {
id = 'Mission', id = 'Mission',
params = { params = {
airborne = self:IsAir(), airborne = self:IsAir(), -- This is important to make aircraft land without respawning them (which was a long standing DCS issue).
route = {points = Points}, route = {points = Points},
}, },
} }
self:T3( { DCSTask } )
return DCSTask return DCSTask
end end
@ -3817,9 +3888,10 @@ function POSITIONABLE:IsSubmarine()
return nil return nil
end end
--- Sets the controlled group to go at the specified speed in meters per second. --- Sets the controlled group to go at the specified speed in meters per second.
-- @param #CONTROLLABLE self -- @param #CONTROLLABLE self
-- @param #number Speed Speed in meters per second. -- @param #number Speed Speed in meters per second
-- @param #boolean Keep (Optional) When set to true, will maintain the speed on passing waypoints. If not present or false, the controlled group will return to the speed as defined by their route. -- @param #boolean Keep (Optional) When set to true, will maintain the speed on passing waypoints. If not present or false, the controlled group will return to the speed as defined by their route.
-- @return #CONTROLLABLE self -- @return #CONTROLLABLE self
function CONTROLLABLE:SetSpeed(Speed, Keep) function CONTROLLABLE:SetSpeed(Speed, Keep)

View File

@ -35,7 +35,7 @@ IDENTIFIABLE = {
local _CategoryName = { local _CategoryName = {
[Unit.Category.AIRPLANE] = "Airplane", [Unit.Category.AIRPLANE] = "Airplane",
[Unit.Category.HELICOPTER] = "Helicoper", [Unit.Category.HELICOPTER] = "Helicopter",
[Unit.Category.GROUND_UNIT] = "Ground Identifiable", [Unit.Category.GROUND_UNIT] = "Ground Identifiable",
[Unit.Category.SHIP] = "Ship", [Unit.Category.SHIP] = "Ship",
[Unit.Category.STRUCTURE] = "Structure", [Unit.Category.STRUCTURE] = "Structure",
@ -56,8 +56,7 @@ end
-- If the Identifiable is not alive, nil is returned. -- If the Identifiable is not alive, nil is returned.
-- If the Identifiable is alive, true is returned. -- If the Identifiable is alive, true is returned.
-- @param #IDENTIFIABLE self -- @param #IDENTIFIABLE self
-- @return #boolean true if Identifiable is alive. -- @return #boolean true if Identifiable is alive or `#nil` if the Identifiable is not existing or is not alive.
-- @return #nil if the Identifiable is not existing or is not alive.
function IDENTIFIABLE:IsAlive() function IDENTIFIABLE:IsAlive()
self:F3( self.IdentifiableName ) self:F3( self.IdentifiableName )
@ -77,11 +76,8 @@ end
--- Returns DCS Identifiable object name. --- Returns DCS Identifiable object name.
-- The function provides access to non-activated objects too. -- The function provides access to non-activated objects too.
-- @param #IDENTIFIABLE self -- @param #IDENTIFIABLE self
-- @return #string The name of the DCS Identifiable. -- @return #string The name of the DCS Identifiable or `#nil`.
-- @return #nil The DCS Identifiable is not existing or alive.
function IDENTIFIABLE:GetName() function IDENTIFIABLE:GetName()
self:F2( self.IdentifiableName )
local IdentifiableName = self.IdentifiableName local IdentifiableName = self.IdentifiableName
return IdentifiableName return IdentifiableName
end end
@ -148,8 +144,7 @@ end
--- Returns coalition of the Identifiable. --- Returns coalition of the Identifiable.
-- @param #IDENTIFIABLE self -- @param #IDENTIFIABLE self
-- @return DCS#coalition.side The side of the coalition. -- @return DCS#coalition.side The side of the coalition or `#nil` The DCS Identifiable is not existing or alive.
-- @return #nil The DCS Identifiable is not existing or alive.
function IDENTIFIABLE:GetCoalition() function IDENTIFIABLE:GetCoalition()
self:F2( self.IdentifiableName ) self:F2( self.IdentifiableName )
@ -190,8 +185,7 @@ end
--- Returns country of the Identifiable. --- Returns country of the Identifiable.
-- @param #IDENTIFIABLE self -- @param #IDENTIFIABLE self
-- @return DCS#country.id The country identifier. -- @return DCS#country.id The country identifier or `#nil` The DCS Identifiable is not existing or alive.
-- @return #nil The DCS Identifiable is not existing or alive.
function IDENTIFIABLE:GetCountry() function IDENTIFIABLE:GetCountry()
self:F2( self.IdentifiableName ) self:F2( self.IdentifiableName )
@ -222,8 +216,7 @@ end
--- Returns Identifiable descriptor. Descriptor type depends on Identifiable category. --- Returns Identifiable descriptor. Descriptor type depends on Identifiable category.
-- @param #IDENTIFIABLE self -- @param #IDENTIFIABLE self
-- @return DCS#Object.Desc The Identifiable descriptor. -- @return DCS#Object.Desc The Identifiable descriptor or `#nil` The DCS Identifiable is not existing or alive.
-- @return #nil The DCS Identifiable is not existing or alive.
function IDENTIFIABLE:GetDesc() function IDENTIFIABLE:GetDesc()
self:F2( self.IdentifiableName ) self:F2( self.IdentifiableName )
@ -242,8 +235,7 @@ end
--- Check if the Object has the attribute. --- Check if the Object has the attribute.
-- @param #IDENTIFIABLE self -- @param #IDENTIFIABLE self
-- @param #string AttributeName The attribute name. -- @param #string AttributeName The attribute name.
-- @return #boolean true if the attribute exists. -- @return #boolean true if the attribute exists or `#nil` The DCS Identifiable is not existing or alive.
-- @return #nil The DCS Identifiable is not existing or alive.
function IDENTIFIABLE:HasAttribute( AttributeName ) function IDENTIFIABLE:HasAttribute( AttributeName )
self:F2( self.IdentifiableName ) self:F2( self.IdentifiableName )
@ -266,8 +258,10 @@ function IDENTIFIABLE:GetCallsign()
return '' return ''
end end
--- Gets the threat level.
-- @param #IDENTIFIABLE self
-- @return #number Threat level.
-- @return #string Type.
function IDENTIFIABLE:GetThreatLevel() function IDENTIFIABLE:GetThreatLevel()
return 0, "Scenery" return 0, "Scenery"
end end

View File

@ -13,7 +13,7 @@
-- --
-- ### Author: **funkyfranky** -- ### Author: **funkyfranky**
-- @module Wrapper.Marker -- @module Wrapper.Marker
-- @image Wrapper_Marker.png -- @image MOOSE_Core.JPG
--- Marker class. --- Marker class.
-- @type MARKER -- @type MARKER
@ -150,7 +150,7 @@ _MARKERID = 0
--- Marker class version. --- Marker class version.
-- @field #string version -- @field #string version
MARKER.version = "0.1.0" MARKER.version="0.1.1"
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- TODO list -- TODO list
@ -175,7 +175,9 @@ function MARKER:New( Coordinate, Text )
-- Inherit everything from FSM class. -- Inherit everything from FSM class.
local self = BASE:Inherit( self, FSM:New() ) -- #MARKER local self = BASE:Inherit( self, FSM:New() ) -- #MARKER
self.coordinate = Coordinate local self=BASE:Inherit(self, FSM:New()) -- #MARKER
self.coordinate=UTILS.DeepCopy(Coordinate)
self.text = Text self.text = Text
@ -315,6 +317,16 @@ function MARKER:ReadOnly()
return self return self
end end
--- Marker is readonly. Text cannot be changed and marker cannot be removed.
-- @param #MARKER self
-- @return #MARKER self
function MARKER:ReadWrite()
self.readonly=false
return self
end
--- Set message that is displayed on screen if the marker is added. --- Set message that is displayed on screen if the marker is added.
-- @param #MARKER self -- @param #MARKER self
-- @param #string Text Message displayed when the marker is added. -- @param #string Text Message displayed when the marker is added.
@ -580,7 +592,7 @@ end
--- Set text that is displayed in the marker panel. Note this does not show the marker. --- Set text that is displayed in the marker panel. Note this does not show the marker.
-- @param #MARKER self -- @param #MARKER self
-- @param #string Text Marker text. Default is an empty sting "". -- @param #string Text Marker text. Default is an empty string "".
-- @return #MARKER self -- @return #MARKER self
function MARKER:SetText( Text ) function MARKER:SetText( Text )
self.text = Text and tostring( Text ) or "" self.text = Text and tostring( Text ) or ""
@ -637,7 +649,9 @@ function MARKER:OnEventMarkRemoved( EventData )
local MarkID = EventData.MarkID local MarkID = EventData.MarkID
self:T3( self.lid .. string.format( "Captured event MarkAdded for Mark ID=%s", tostring( MarkID ) ) ) local MarkID=EventData.MarkID
self:T3(self.lid..string.format("Captured event MarkRemoved for Mark ID=%s", tostring(MarkID)))
if MarkID == self.mid then if MarkID == self.mid then
@ -664,16 +678,22 @@ function MARKER:OnEventMarkChange( EventData )
if MarkID == self.mid then if MarkID == self.mid then
local MarkID=EventData.MarkID
self:T3(self.lid..string.format("Captured event MarkChange for Mark ID=%s", tostring(MarkID)))
if MarkID==self.mid then
self.text=tostring(EventData.MarkText)
self:Changed(EventData) self:Changed(EventData)
self:TextChanged( tostring( EventData.MarkText ) )
end end
end end
end end
end
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
-- FSM Event Functions -- FSM Event Functions
------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------

View File

@ -384,7 +384,7 @@ function POSITIONABLE:GetCoordinate()
local coord=COORDINATE:NewFromVec3(PositionableVec3) local coord=COORDINATE:NewFromVec3(PositionableVec3)
local heading = self:GetHeading() local heading = self:GetHeading()
coord.Heading = heading coord.Heading = heading
-- Return a new coordinate object. -- Return a new coordiante object.
return coord return coord
end end
@ -779,11 +779,11 @@ function POSITIONABLE:GetRelativeVelocity( Positionable )
return UTILS.VecNorm( vtot ) return UTILS.VecNorm( vtot )
end end
--- Returns the POSITIONABLE height above sea level in meters. --- Returns the POSITIONABLE height above sea level in meters.
-- @param Wrapper.Positionable#POSITIONABLE self -- @param Wrapper.Positionable#POSITIONABLE self
-- @return DCS#Vec3 The height of the POSITIONABLE in meters. -- @return DCS#Vec3 Height of the positionable in meters (or nil, if the object does not exist).
-- @return #nil The POSITIONABLE is not existing or alive. function POSITIONABLE:GetHeight() --R2.1
function POSITIONABLE:GetHeight()
self:F2( self.PositionableName ) self:F2( self.PositionableName )
local DCSPositionable = self:GetDCSObject() local DCSPositionable = self:GetDCSObject()
@ -1232,6 +1232,33 @@ function POSITIONABLE:MessageToGroup( Message, Duration, MessageGroup, Name )
return nil return nil
end end
--- Send a message to a @{Wrapper.Unit}.
-- The message will appear in the message area. The message will begin with the callsign of the group and the type of the first unit sending the message.
-- @param #POSITIONABLE self
-- @param #string Message The message text
-- @param DCS#Duration Duration The duration of the message.
-- @param Wrapper.Unit#UNIT MessageUnit The UNIT object receiving the message.
-- @param #string Name (optional) The Name of the sender. If not provided, the Name is the type of the Positionable.
function POSITIONABLE:MessageToUnit( Message, Duration, MessageUnit, Name )
self:F2( { Message, Duration } )
local DCSObject = self:GetDCSObject()
if DCSObject then
if DCSObject:isExist() then
if MessageUnit:IsAlive() then
self:GetMessage( Message, Duration, Name ):ToUnit( MessageUnit )
else
BASE:E( { "Message not sent to Unit; Unit is not alive...", Message = Message, MessageUnit = MessageUnit } )
end
else
BASE:E( { "Message not sent to Unit; Positionable is not alive ...", Message = Message, Positionable = self, MessageUnit = MessageUnit } )
end
end
return nil
end
--- Send a message of a message type to a @{Wrapper.Group}. --- Send a message of a message type to a @{Wrapper.Group}.
-- The message will appear in the message area. The message will begin with the callsign of the group and the type of the first unit sending the message. -- The message will appear in the message area. The message will begin with the callsign of the group and the type of the first unit sending the message.
-- @param #POSITIONABLE self -- @param #POSITIONABLE self
@ -1298,6 +1325,30 @@ function POSITIONABLE:MessageToSetUnit( Message, Duration, MessageSetUnit, Name
return nil return nil
end end
--- Send a message to a @{Core.Set#SET_UNIT}.
-- The message will appear in the message area. The message will begin with the callsign of the group and the type of the first unit sending the message.
-- @param #POSITIONABLE self
-- @param #string Message The message text
-- @param DCS#Duration Duration The duration of the message.
-- @param Core.Set#SET_UNIT MessageSetUnit The SET_UNIT collection receiving the message.
-- @param #string Name (optional) The Name of the sender. If not provided, the Name is the type of the Positionable.
function POSITIONABLE:MessageToSetUnit( Message, Duration, MessageSetUnit, Name )
self:F2( { Message, Duration } )
local DCSObject = self:GetDCSObject()
if DCSObject then
if DCSObject:isExist() then
MessageSetUnit:ForEachUnit(
function( MessageGroup )
self:GetMessage( Message, Duration, Name ):ToUnit( MessageGroup )
end
)
end
end
return nil
end
--- Send a message to the players in the @{Wrapper.Group}. --- Send a message to the players in the @{Wrapper.Group}.
-- The message will appear in the message area. The message will begin with the callsign of the group and the type of the first unit sending the message. -- The message will appear in the message area. The message will begin with the callsign of the group and the type of the first unit sending the message.
-- @param #POSITIONABLE self -- @param #POSITIONABLE self
@ -1480,17 +1531,15 @@ do -- Cargo
return ItemCount return ItemCount
end end
-- --- Get Cargo Bay Free Volume in m3. --- Get the number of infantry soldiers that can be embarked into an aircraft (airplane or helicopter).
-- -- @param #POSITIONABLE self -- Returns `nil` for ground or ship units.
-- -- @return #number CargoBayFreeVolume -- @param #POSITIONABLE self
-- function POSITIONABLE:GetCargoBayFreeVolume() -- @return #number Descent number of soldiers that fit into the unit. Returns `#nil` for ground and ship units.
-- local CargoVolume = 0 function POSITIONABLE:GetTroopCapacity()
-- for CargoName, Cargo in pairs( self.__.Cargo ) do local DCSunit=self:GetDCSObject() --DCS#Unit
-- CargoVolume = CargoVolume + Cargo:GetVolume() local capacity=DCSunit:getDescentCapacity()
-- end return capacity
-- return self.__.CargoBayVolumeLimit - CargoVolume end
-- end
--
--- Get Cargo Bay Free Weight in kg. --- Get Cargo Bay Free Weight in kg.
-- @param #POSITIONABLE self -- @param #POSITIONABLE self
@ -1509,40 +1558,80 @@ do -- Cargo
return self.__.CargoBayWeightLimit - CargoWeight return self.__.CargoBayWeightLimit - CargoWeight
end end
-- --- Get Cargo Bay Volume Limit in m3.
-- -- @param #POSITIONABLE self
-- -- @param #number VolumeLimit
-- function POSITIONABLE:SetCargoBayVolumeLimit( VolumeLimit )
-- self.__.CargoBayVolumeLimit = VolumeLimit
-- end
--- Set Cargo Bay Weight Limit in kg. --- Set Cargo Bay Weight Limit in kg.
-- @param #POSITIONABLE self -- @param #POSITIONABLE self
-- @param #number WeightLimit -- @param #number WeightLimit (Optional) Weight limit in kg. If not given, the value is taken from the descriptors or hard coded.
function POSITIONABLE:SetCargoBayWeightLimit( WeightLimit ) function POSITIONABLE:SetCargoBayWeightLimit( WeightLimit )
if WeightLimit then if WeightLimit then
---
-- User defined value
---
self.__.CargoBayWeightLimit = WeightLimit self.__.CargoBayWeightLimit = WeightLimit
elseif self.__.CargoBayWeightLimit ~= nil then elseif self.__.CargoBayWeightLimit ~= nil then
-- Value already set ==> Do nothing! -- Value already set ==> Do nothing!
else else
-- If WeightLimit is not provided, we will calculate it depending on the type of unit. ---
-- Weightlimit is not provided, we will calculate it depending on the type of unit.
---
-- Descriptors that contain the type name and for aircraft also weights.
local Desc = self:GetDesc()
self:F({Desc=Desc})
-- Unit type name.
local TypeName=Desc.typeName or "Unknown Type"
-- When an airplane or helicopter, we calculate the WeightLimit based on the descriptor. -- When an airplane or helicopter, we calculate the WeightLimit based on the descriptor.
if self:IsAir() then if self:IsAir() then
local Desc = self:GetDesc()
self:F( { Desc = Desc } )
-- Max takeoff weight if DCS descriptors have unrealstic values.
local Weights = { local Weights = {
["C-17A"] = 35000, -- 77519 cannot be used, because it loads way too many APCs and infantry. -- C-17A
["C-130"] = 22000 -- The real value cannot be used, because it loads way too many APCs and infantry. -- Wiki says: max=265,352, empty=128,140, payload=77,516 (134 troops, 1 M1 Abrams tank, 2 M2 Bradley or 3 Stryker)
-- DCS says: max=265,350, empty=125,645, fuel=132,405 ==> Cargo Bay=7300 kg with a full fuel load (lot of fuel!) and 73300 with half a fuel load.
--["C-17A"] = 35000, --77519 cannot be used, because it loads way too much apcs and infantry.
-- C-130:
-- DCS says: max=79,380, empty=36,400, fuel=10,415 kg ==> Cargo Bay=32,565 kg with fuel load.
-- Wiki says: max=70,307, empty=34,382, payload=19,000 kg (92 passengers, 2-3 Humvees or 2 M113s), max takeoff weight 70,037 kg.
-- Here we say two M113s should be transported. Each one weights 11,253 kg according to DCS. So the cargo weight should be 23,000 kg with a full load of fuel.
-- This results in a max takeoff weight of 69,815 kg (23,000+10,415+36,400), which is very close to the Wiki value of 70,037 kg.
["C-130"] = 70000,
} }
self.__.CargoBayWeightLimit = Weights[Desc.typeName] or (Desc.massMax - (Desc.massEmpty + Desc.fuelMassMax)) -- Max (takeoff) weight (empty+fuel+cargo weight).
elseif self:IsShip() then local massMax= Desc.massMax or 0
local Desc = self:GetDesc()
self:F( { Desc = Desc } )
-- Adjust value if set above.
local maxTakeoff=Weights[TypeName]
if maxTakeoff then
massMax=maxTakeoff
end
-- Empty weight.
local massEmpty=Desc.massEmpty or 0
-- Fuel. The descriptor provides the max fuel mass in kg. This needs to be multiplied by the relative fuel amount to calculate the actual fuel mass on board.
local massFuelMax=Desc.fuelMassMax or 0
local relFuel=math.min(self:GetFuel() or 1.0, 1.0) -- We take 1.0 as max in case of external fuel tanks.
local massFuel=massFuelMax*relFuel
-- Number of soldiers according to DCS function
--local troopcapacity=self:GetTroopCapacity() or 0
-- Calculate max cargo weight, which is the max (takeoff) weight minus the empty weight minus the actual fuel weight.
local CargoWeight=massMax-(massEmpty+massFuel)
-- Debug info.
self:T(string.format("Setting Cargo bay weight limit [%s]=%d kg (Mass max=%d, empty=%d, fuelMax=%d kg (rel=%.3f), fuel=%d kg", TypeName, CargoWeight, massMax, massEmpty, massFuelMax, relFuel, massFuel))
--self:T(string.format("Descent Troop Capacity=%d ==> %d kg (for 95 kg soldier)", troopcapacity, troopcapacity*95))
-- Set value.
self.__.CargoBayWeightLimit = CargoWeight
elseif self:IsShip() then
-- Hard coded cargo weights in kg.
local Weights = { local Weights = {
["Type_071"] = 245000, ["Type_071"] = 245000,
["LHA_Tarawa"] = 500000, ["LHA_Tarawa"] = 500000,
@ -1551,13 +1640,15 @@ do -- Cargo
["Dry-cargo ship-2"] = 70000, ["Dry-cargo ship-2"] = 70000,
["Higgins_boat"] = 3700, -- Higgins Boat can load 3700 kg of general cargo or 36 men (source wikipedia). ["Higgins_boat"] = 3700, -- Higgins Boat can load 3700 kg of general cargo or 36 men (source wikipedia).
["USS_Samuel_Chase"] = 25000, -- Let's say 25 tons for now. Wiki says 33 Higgins boats, which would be 264 tons (can't be right!) and/or 578 troops. ["USS_Samuel_Chase"] = 25000, -- Let's say 25 tons for now. Wiki says 33 Higgins boats, which would be 264 tons (can't be right!) and/or 578 troops.
["LST_Mk2"] = 2100000 -- Can carry 2100 tons according to wiki source! ["LST_Mk2"] = 2100000, -- Can carry 2100 tons according to wiki source!
["speedboat"] = 500, -- 500 kg ~ 5 persons
["Seawise_Giant"] =261000000, -- Gross tonnage is 261,000 tonns.
} }
self.__.CargoBayWeightLimit = (Weights[Desc.typeName] or 50000) self.__.CargoBayWeightLimit = ( Weights[TypeName] or 50000 )
else else
local Desc = self:GetDesc()
-- Hard coded number of soldiers.
local Weights = { local Weights = {
["AAV7"] = 25, ["AAV7"] = 25,
["Bedford_MWD"] = 8, -- new by kappa ["Bedford_MWD"] = 8, -- new by kappa
@ -1593,7 +1684,7 @@ do -- Cargo
["KrAZ6322"] = 12, ["KrAZ6322"] = 12,
["M 818"] = 12, ["M 818"] = 12,
["Tigr_233036"] = 6, ["Tigr_233036"] = 6,
["TPZ"] = 10, ["TPZ"] = 10, -- Fuchs
["UAZ-469"] = 4, -- new by kappa ["UAZ-469"] = 4, -- new by kappa
["Ural-375"] = 12, ["Ural-375"] = 12,
["Ural-4320-31"] = 14, ["Ural-4320-31"] = 14,
@ -1607,12 +1698,28 @@ do -- Cargo
["HL_DSHK"] = 6, ["HL_DSHK"] = 6,
} }
local CargoBayWeightLimit = (Weights[Desc.typeName] or 0) * 95 -- Assuming that each passenger weighs 95 kg on average.
local CargoBayWeightLimit = ( Weights[TypeName] or 0 ) * 95
self.__.CargoBayWeightLimit = CargoBayWeightLimit self.__.CargoBayWeightLimit = CargoBayWeightLimit
end end
end end
self:F({CargoBayWeightLimit = self.__.CargoBayWeightLimit}) self:F({CargoBayWeightLimit = self.__.CargoBayWeightLimit})
end end
--- Get Cargo Bay Weight Limit in kg.
-- @param #POSITIONABLE self
-- @return #number Max cargo weight in kg.
function POSITIONABLE:GetCargoBayWeightLimit()
if self.__.CargoBayWeightLimit==nil then
self:SetCargoBayWeightLimit()
end
return self.__.CargoBayWeightLimit
end
end --- Cargo end --- Cargo
--- Signal a flare at the position of the POSITIONABLE. --- Signal a flare at the position of the POSITIONABLE.

View File

@ -57,3 +57,40 @@ end
function SCENERY:GetThreatLevel() function SCENERY:GetThreatLevel()
return 0, "Scenery" return 0, "Scenery"
end end
--- Find a SCENERY object by it's name/id.
--@param #SCENERY self
--@param #string name The name/id of the scenery object as taken from the ME. Ex. '595785449'
--@return #SCENERY Scenery Object or nil if not found.
function SCENERY:FindByName(name)
local findAirbase = function ()
local airbases = AIRBASE.GetAllAirbases()
for index,airbase in pairs(airbases) do
local surftype = airbase:GetCoordinate():GetSurfaceType()
if surftype ~= land.SurfaceType.SHALLOW_WATER and surftype ~= land.SurfaceType.WATER then
return airbase:GetCoordinate()
end
end
return nil
end
local sceneryScan = function (scancoord)
if scancoord ~= nil then
local _,_,sceneryfound,_,_,scenerylist = scancoord:ScanObjects(200, false, false, true)
if sceneryfound == true then
scenerylist[1].id_ = name
SCENERY.SceneryObject = SCENERY:Register(scenerylist[1].id_, scenerylist[1])
return SCENERY.SceneryObject
end
end
return nil
end
if SCENERY.SceneryObject then
SCENERY.SceneryObject.SceneryObject.id_ = name
SCENERY.SceneryObject.SceneryName = name
return SCENERY:Register(SCENERY.SceneryObject.SceneryObject.id_, SCENERY.SceneryObject.SceneryObject)
else
return sceneryScan(findAirbase())
end
end