YUKA

v0.7.7

    Classes

    • AABB
      Members
      • max
      • min
      Methods
      • applyMatrix4
      • clampPoint
      • clone
      • containsPoint
      • copy
      • equals
      • expand
      • fromCenterAndSize
      • fromJSON
      • fromPoints
      • getCenter
      • getNormalFromSurfacePoint
      • getSize
      • intersectsAABB
      • intersectsBoundingSphere
      • intersectsPlane
      • set
      • toJSON
    • AlignmentBehavior
      Members
      • active
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • ArriveBehavior
      Members
      • active
      • deceleration
      • target
      • tolerance
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • AStar
      Members
      • found
      • graph
      • heuristic
      • source
      • target
      Methods
      • clear
      • getPath
      • getSearchTree
      • search
    • BFS
      Members
      • found
      • graph
      • source
      • target
      Methods
      • clear
      • getPath
      • getSearchTree
      • search
    • BoundingSphere
      Members
      • center
      • radius
      Methods
      • applyMatrix4
      • clampPoint
      • clone
      • containsPoint
      • copy
      • equals
      • fromJSON
      • fromPoints
      • getNormalFromSurfacePoint
      • intersectsBoundingSphere
      • intersectsPlane
      • set
      • toJSON
    • BVH
      Members
      • branchingFactor
      • depth
      • primitivesPerNode
      • root
      Methods
      • fromMeshGeometry
      • traverse
    • BVHNode
      Members
      • boundingVolume
      • centroids
      • children
      • parent
      • primitives
      Methods
      • build
      • computeBoundingVolume
      • computeSplitAxis
      • getDepth
      • intersectRay
      • intersectsRay
      • leaf
      • root
      • split
      • traverse
    • Cell
      Members
      • aabb
      • entries
      Methods
      • add
      • empty
      • fromJSON
      • intersects
      • makeEmpty
      • remove
      • resolveReferences
      • toJSON
    • CellSpacePartitioning
      Members
      • cells
      • cellsX
      • cellsY
      • cellsZ
      • depth
      • height
      • width
      Methods
      • addEntityToPartition
      • addPolygon
      • fromJSON
      • getIndexForPosition
      • makeEmpty
      • query
      • removeEntityFromPartition
      • resolveReferences
      • toJSON
      • updateEntity
    • CohesionBehavior
      Members
      • active
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • CompositeGoal
      Members
      • owner
      • status
      • subgoals
      Methods
      • activate
      • activateIfInactive
      • active
      • addSubgoal
      • clearSubgoals
      • completed
      • currentSubgoal
      • execute
      • executeSubgoals
      • failed
      • fromJSON
      • handleMessage
      • hasSubgoals
      • inactive
      • removeSubgoal
      • replanIfFailed
      • resolveReferences
      • terminate
      • toJSON
    • ConvexHull
      Members
      • centroid
      • edges
      • faces
      • mergeFaces
      • vertices
      Methods
      • computeCentroid
      • computeUniqueEdges
      • computeUniqueVertices
      • containsPoint
      • fromAABB
      • fromPoints
      • intersectsAABB
      • intersectsConvexHull
    • Corridor
      Members
      • portalEdges
      Methods
      • generate
      • push
    • CostTable
      Methods
      • clear
      • fromJSON
      • get
      • init
      • set
      • size
      • toJSON
    • DFS
      Members
      • found
      • graph
      • source
      • target
      Methods
      • clear
      • getPath
      • getSearchTree
      • search
    • Dijkstra
      Members
      • found
      • graph
      • source
      • target
      Methods
      • clear
      • getPath
      • getSearchTree
      • search
    • Edge
      Members
      • cost
      • from
      • to
      Methods
      • clone
      • copy
      • fromJSON
      • toJSON
    • EntityManager
      Members
      • entities
      • spatialIndex
      Methods
      • add
      • clear
      • fromJSON
      • getEntityByName
      • processTrigger
      • registerType
      • remove
      • sendMessage
      • toJSON
      • update
      • updateEntity
      • updateNeighborhood
    • EvadeBehavior
      Members
      • active
      • panicDistance
      • predictionFactor
      • pursuer
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • EventDispatcher
      Methods
      • addEventListener
      • dispatchEvent
      • hasEventListener
      • removeEventListener
    • FleeBehavior
      Members
      • active
      • panicDistance
      • target
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • FollowPathBehavior
      Members
      • active
      • nextWaypointDistance
      • path
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • FuzzyAND
      Members
      • terms
      Methods
      • clearDegreeOfMembership
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • FuzzyCompositeTerm
      Members
      • terms
      Methods
      • clearDegreeOfMembership
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • FuzzyFAIRLY
      Members
      • terms
      Methods
      • clearDegreeOfMembership
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • FuzzyModule
      Members
      • flvs
      • rules
      Methods
      • addFLV
      • addRule
      • defuzzify
      • fromJSON
      • fuzzify
      • removeFLV
      • removeRule
      • toJSON
    • FuzzyOR
      Members
      • terms
      Methods
      • clearDegreeOfMembership
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • FuzzyRule
      Members
      • antecedent
      • consequence
      Methods
      • evaluate
      • fromJSON
      • initConsequence
      • toJSON
    • FuzzySet
      Members
      • degreeOfMembership
      • left
      • representativeValue
      • right
      • uuid
      Methods
      • clearDegreeOfMembership
      • computeDegreeOfMembership
      • fromJSON
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • FuzzyTerm
      Methods
      • clearDegreeOfMembership
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • FuzzyVariable
      Members
      • fuzzySets
      • maxRange
      • minRange
      Methods
      • add
      • defuzzifyCentroid
      • defuzzifyMaxAv
      • fromJSON
      • fuzzify
      • remove
      • toJSON
    • FuzzyVERY
      Members
      • terms
      Methods
      • clearDegreeOfMembership
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • GameEntity
      Members
      • active
      • boundingRadius
      • canActivateTrigger
      • children
      • forward
      • manager
      • maxTurnRate
      • name
      • neighborhoodRadius
      • neighbors
      • parent
      • position
      • rotation
      • scale
      • up
      • updateNeighborhood
      • uuid
      • worldMatrix
      Methods
      • add
      • fromJSON
      • getDirection
      • getWorldDirection
      • getWorldPosition
      • handleMessage
      • lineOfSightTest
      • lookAt
      • remove
      • resolveReferences
      • rotateTo
      • sendMessage
      • setRenderComponent
      • start
      • toJSON
      • update
    • Goal
      Members
      • owner
      • status
      Methods
      • activate
      • activateIfInactive
      • active
      • completed
      • execute
      • failed
      • fromJSON
      • handleMessage
      • inactive
      • replanIfFailed
      • resolveReferences
      • terminate
      • toJSON
    • GoalEvaluator
      Members
      • characterBias
      Methods
      • calculateDesirability
      • fromJSON
      • setGoal
      • toJSON
    • Graph
      Members
      • digraph
      Methods
      • addEdge
      • addNode
      • clear
      • fromJSON
      • getEdge
      • getEdgeCount
      • getEdgesOfNode
      • getNode
      • getNodeCount
      • getNodes
      • hasEdge
      • hasNode
      • removeEdge
      • removeNode
      • toJSON
    • GraphUtils
      Methods
      • createGridLayout
    • HalfEdge
      Members
      • next
      • polygon
      • prev
      • twin
      • vertex
      Methods
      • getDirection
      • head
      • length
      • linkOpponent
      • squaredLength
      • tail
    • HeuristicPolicyDijkstra
      Methods
      • calculate
    • HeuristicPolicyEuclid
      Methods
      • calculate
    • HeuristicPolicyEuclidSquared
      Methods
      • calculate
    • HeuristicPolicyManhattan
      Methods
      • calculate
    • InterposeBehavior
      Members
      • active
      • deceleration
      • entity1
      • entity2
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • LeftSCurveFuzzySet
      Members
      • degreeOfMembership
      • left
      • midpoint
      • representativeValue
      • right
      • uuid
      Methods
      • clearDegreeOfMembership
      • computeDegreeOfMembership
      • fromJSON
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • LeftShoulderFuzzySet
      Members
      • degreeOfMembership
      • left
      • midpoint
      • representativeValue
      • right
      • uuid
      Methods
      • clearDegreeOfMembership
      • computeDegreeOfMembership
      • fromJSON
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • LineSegment
      Members
      • from
      • to
      Methods
      • at
      • clone
      • closestPointToPoint
      • closestPointToPointParameter
      • copy
      • delta
      • equals
      • set
    • Logger
      Methods
      • error
      • log
      • setLevel
      • warn
    • MathUtils
      Methods
      • area
      • argmax
      • choice
      • clamp
      • generateUUID
      • randFloat
      • randInt
    • Matrix3
      Members
      • elements
      Methods
      • clone
      • copy
      • eigenDecomposition
      • equals
      • extractBasis
      • frobeniusNorm
      • fromArray
      • fromMatrix4
      • fromQuaternion
      • getElementIndex
      • identity
      • lookAt
      • makeBasis
      • multiply
      • multiplyMatrices
      • multiplyScalar
      • offDiagonalFrobeniusNorm
      • premultiply
      • set
      • shurDecomposition
      • toArray
      • transpose
    • Matrix4
      Members
      • elements
      Methods
      • clone
      • compose
      • copy
      • equals
      • extractBasis
      • fromArray
      • fromMatrix3
      • fromQuaternion
      • getInverse
      • getMaxScale
      • identity
      • makeBasis
      • multiply
      • multiplyMatrices
      • multiplyScalar
      • premultiply
      • scale
      • set
      • setPosition
      • toArray
      • transpose
    • MemoryRecord
      Members
      • entity
      • lastSensedPosition
      • timeBecameVisible
      • timeLastSensed
      • visible
      Methods
      • fromJSON
      • resolveReferences
      • toJSON
    • MemorySystem
      Members
      • memorySpan
      • owner
      • records
      • recordsMap
      Methods
      • clear
      • createRecord
      • deleteRecord
      • fromJSON
      • getRecord
      • getValidMemoryRecords
      • hasRecord
      • resolveReferences
      • toJSON
    • MeshGeometry
      Members
      • aabb
      • backfaceCulling
      • boundingSphere
      • indices
      • vertices
      Methods
      • computeBoundingVolume
      • fromJSON
      • intersectRay
      • toJSON
      • toTriangleSoup
    • MessageDispatcher
      Members
      • delayedTelegrams
      Methods
      • clear
      • deliver
      • dispatch
      • dispatchDelayedMessages
      • fromJSON
      • resolveReferences
      • toJSON
    • MovingEntity
      Members
      • active
      • boundingRadius
      • canActivateTrigger
      • children
      • forward
      • manager
      • maxSpeed
      • maxTurnRate
      • name
      • neighborhoodRadius
      • neighbors
      • parent
      • position
      • rotation
      • scale
      • up
      • updateNeighborhood
      • updateOrientation
      • uuid
      • velocity
      • worldMatrix
      Methods
      • add
      • fromJSON
      • getDirection
      • getSpeed
      • getSpeedSquared
      • getWorldDirection
      • getWorldPosition
      • handleMessage
      • lineOfSightTest
      • lookAt
      • remove
      • resolveReferences
      • rotateTo
      • sendMessage
      • setRenderComponent
      • start
      • toJSON
      • update
    • NavEdge
      Members
      • cost
      • from
      • to
      Methods
      • clone
      • copy
      • fromJSON
      • toJSON
    • NavMesh
      Members
      • epsilonContainsTest
      • epsilonCoplanarTest
      • graph
      • mergeConvexRegions
      • regions
      • spatialIndex
      Methods
      • clampMovement
      • clear
      • findPath
      • fromPolygons
      • getClosestRegion
      • getNodeIndex
      • getRandomRegion
      • getRegionForPoint
      • updateSpatialIndex
    • NavMeshLoader
      Methods
      • load
      • parse
    • NavNode
      Members
      • index
      • position
      • userData
      Methods
      • fromJSON
      • toJSON
    • Node
      Members
      • index
      Methods
      • fromJSON
      • toJSON
    • NormalDistFuzzySet
      Members
      • degreeOfMembership
      • left
      • midpoint
      • representativeValue
      • right
      • standardDeviation
      • uuid
      Methods
      • clearDegreeOfMembership
      • computeDegreeOfMembership
      • fromJSON
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • OBB
      Members
      • center
      • halfSizes
      • rotation
      Methods
      • clampPoint
      • clone
      • containsPoint
      • copy
      • equals
      • fromAABB
      • fromJSON
      • fromPoints
      • getSize
      • intersectsAABB
      • intersectsBoundingSphere
      • intersectsOBB
      • intersectsPlane
      • set
      • toJSON
    • ObstacleAvoidanceBehavior
      Members
      • active
      • brakingWeight
      • dBoxMinLength
      • obstacles
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • OffsetPursuitBehavior
      Members
      • active
      • leader
      • offset
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • OnPathBehavior
      Members
      • active
      • path
      • predictionFactor
      • radius
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • Path
      Members
      • loop
      Methods
      • add
      • advance
      • clear
      • current
      • finished
      • fromJSON
      • toJSON
    • Plane
      Members
      • constant
      • normal
      Methods
      • clone
      • copy
      • distanceToPoint
      • equals
      • fromCoplanarPoints
      • fromNormalAndCoplanarPoint
      • intersectPlane
      • intersectsPlane
      • projectPoint
      • set
    • Polygon
      Members
      • centroid
      • edge
      • plane
      Methods
      • computeCentroid
      • contains
      • convex
      • coplanar
      • distanceToPoint
      • fromContour
      • getContour
    • Polyhedron
      Members
      • centroid
      • edges
      • faces
      • vertices
      Methods
      • computeCentroid
      • computeUniqueEdges
      • computeUniqueVertices
      • fromAABB
    • PriorityQueue
      Members
      • compare
      • data
      • length
      Methods
      • peek
      • pop
      • push
    • PursuitBehavior
      Members
      • active
      • evader
      • predictionFactor
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • Quaternion
      Members
      • w
      • x
      • y
      • z
      Methods
      • angleTo
      • clone
      • conjugate
      • copy
      • dot
      • equals
      • extractRotationFromMatrix
      • fromArray
      • fromEuler
      • fromMatrix3
      • inverse
      • length
      • lookAt
      • multiply
      • multiplyQuaternions
      • normalize
      • premultiply
      • rotateTo
      • set
      • slerp
      • squaredLength
      • toArray
      • toEuler
    • Ray
      Members
      • direction
      • origin
      Methods
      • applyMatrix4
      • at
      • clone
      • copy
      • equals
      • intersectAABB
      • intersectBoundingSphere
      • intersectBVH
      • intersectConvexHull
      • intersectOBB
      • intersectPlane
      • intersectsAABB
      • intersectsBoundingSphere
      • intersectsBVH
      • intersectsConvexHull
      • intersectsOBB
      • intersectsPlane
      • intersectTriangle
      • set
    • RectangularTriggerRegion
      Members
      • size
      Methods
      • fromJSON
      • toJSON
      • touching
      • update
    • Regulator
      Members
      • updateFrequency
      Methods
      • ready
    • RightSCurveFuzzySet
      Members
      • degreeOfMembership
      • left
      • midpoint
      • representativeValue
      • right
      • uuid
      Methods
      • clearDegreeOfMembership
      • computeDegreeOfMembership
      • fromJSON
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • RightShoulderFuzzySet
      Members
      • degreeOfMembership
      • left
      • midpoint
      • representativeValue
      • right
      • uuid
      Methods
      • clearDegreeOfMembership
      • computeDegreeOfMembership
      • fromJSON
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • SAT
      Methods
      • intersects
    • SeekBehavior
      Members
      • active
      • target
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • SeparationBehavior
      Members
      • active
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • SingletonFuzzySet
      Members
      • degreeOfMembership
      • left
      • midpoint
      • representativeValue
      • right
      • uuid
      Methods
      • clearDegreeOfMembership
      • computeDegreeOfMembership
      • fromJSON
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • Smoother
      Members
      • count
      Methods
      • calculate
      • fromJSON
      • toJSON
    • SphericalTriggerRegion
      Members
      • radius
      Methods
      • fromJSON
      • toJSON
      • touching
      • update
    • State
      Methods
      • enter
      • execute
      • exit
      • fromJSON
      • onMessage
      • resolveReferences
      • toJSON
    • StateMachine
      Members
      • currentState
      • globalState
      • owner
      • previousState
      • states
      Methods
      • add
      • changeTo
      • fromJSON
      • get
      • handleMessage
      • in
      • registerType
      • remove
      • resolveReferences
      • revert
      • toJSON
      • update
    • SteeringBehavior
      Members
      • active
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON
    • SteeringManager
      Members
      • behaviors
      • vehicle
      Methods
      • add
      • calculate
      • clear
      • fromJSON
      • registerType
      • remove
      • resolveReferences
      • toJSON
    • Task
      Methods
      • execute
    • TaskQueue
      Members
      • options
      • tasks
      Methods
      • enqueue
      • update
    • Telegram
      Members
      • data
      • delay
      • message
      • receiver
      • sender
      Methods
      • fromJSON
      • resolveReferences
      • toJSON
    • Think
      Members
      • evaluators
      • owner
      • status
      • subgoals
      Methods
      • activate
      • activateIfInactive
      • active
      • addEvaluator
      • addSubgoal
      • arbitrate
      • clearSubgoals
      • completed
      • currentSubgoal
      • execute
      • executeSubgoals
      • failed
      • fromJSON
      • handleMessage
      • hasSubgoals
      • inactive
      • registerType
      • removeEvaluator
      • removeSubgoal
      • replanIfFailed
      • resolveReferences
      • terminate
      • toJSON
    • Time
      Methods
      • disableFixedDelta
      • dispose
      • enableFixedDelta
      • getDelta
      • getElapsed
      • getFixedDelta
      • getTimescale
      • reset
      • setFixedDelta
      • setTimescale
      • update
    • TriangularFuzzySet
      Members
      • degreeOfMembership
      • left
      • midpoint
      • representativeValue
      • right
      • uuid
      Methods
      • clearDegreeOfMembership
      • computeDegreeOfMembership
      • fromJSON
      • getDegreeOfMembership
      • toJSON
      • updateDegreeOfMembership
    • Trigger
      Members
      • active
      • boundingRadius
      • canActivateTrigger
      • children
      • forward
      • manager
      • maxTurnRate
      • name
      • neighborhoodRadius
      • neighbors
      • parent
      • position
      • region
      • rotation
      • scale
      • up
      • updateNeighborhood
      • uuid
      • worldMatrix
      Methods
      • add
      • check
      • execute
      • fromJSON
      • getDirection
      • getWorldDirection
      • getWorldPosition
      • handleMessage
      • lineOfSightTest
      • lookAt
      • registerType
      • remove
      • resolveReferences
      • rotateTo
      • sendMessage
      • setRenderComponent
      • start
      • toJSON
      • update
      • updateRegion
    • TriggerRegion
      Methods
      • fromJSON
      • toJSON
      • touching
      • update
    • Vector3
      Members
      • x
      • y
      • z
      Methods
      • add
      • addScalar
      • addVectors
      • angleTo
      • applyMatrix4
      • applyRotation
      • clamp
      • clone
      • copy
      • cross
      • crossVectors
      • distanceTo
      • divide
      • divideScalar
      • divideVectors
      • dot
      • equals
      • extractPositionFromMatrix
      • fromArray
      • fromMatrix3Column
      • fromMatrix4Column
      • fromSpherical
      • length
      • manhattanDistanceTo
      • manhattanLength
      • max
      • min
      • multiply
      • multiplyScalar
      • multiplyVectors
      • normalize
      • reflect
      • set
      • squaredDistanceTo
      • squaredLength
      • sub
      • subScalar
      • subVectors
      • toArray
      • transformDirection
    • Vehicle
      Members
      • active
      • boundingRadius
      • canActivateTrigger
      • children
      • forward
      • manager
      • mass
      • maxForce
      • maxSpeed
      • maxTurnRate
      • name
      • neighborhoodRadius
      • neighbors
      • parent
      • position
      • rotation
      • scale
      • smoother
      • steering
      • up
      • updateNeighborhood
      • updateOrientation
      • uuid
      • velocity
      • worldMatrix
      Methods
      • add
      • fromJSON
      • getDirection
      • getSpeed
      • getSpeedSquared
      • getWorldDirection
      • getWorldPosition
      • handleMessage
      • lineOfSightTest
      • lookAt
      • remove
      • resolveReferences
      • rotateTo
      • sendMessage
      • setRenderComponent
      • start
      • toJSON
      • update
    • Vision
      Members
      • fieldOfView
      • obstacles
      • owner
      • range
      Methods
      • addObstacle
      • fromJSON
      • removeObstacle
      • resolveReferences
      • toJSON
      • visible
    • WanderBehavior
      Members
      • active
      • distance
      • jitter
      • radius
      • weight
      Methods
      • calculate
      • fromJSON
      • resolveReferences
      • toJSON

    Global

    • runTaskQueue
    • Triangle
    NHN Entertainment. Frontend Development Lab