summaryrefslogtreecommitdiff
path: root/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs
diff options
context:
space:
mode:
authorchai <215380520@qq.com>2024-05-23 10:08:29 +0800
committerchai <215380520@qq.com>2024-05-23 10:08:29 +0800
commit8722a9920c1f6119bf6e769cba270e63097f8e25 (patch)
tree2eaf9865de7fb1404546de4a4296553d8f68cc3b /Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs
parent3ba4020b69e5971bb0df7ee08b31d10ea4d01937 (diff)
+ astar project
Diffstat (limited to 'Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs')
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobAlignAgentWithMovementDirection.cs43
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobAlignAgentWithMovementDirection.cs.meta11
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobApplyGravity.cs75
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobApplyGravity.cs.meta11
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobControl.cs146
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobControl.cs.meta11
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobDrawFollowerGizmos.cs104
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobDrawFollowerGizmos.cs.meta11
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedMovementOverride.cs45
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedMovementOverride.cs.meta11
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedOffMeshLinkTransition.cs86
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedOffMeshLinkTransition.cs.meta11
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobMoveAgent.cs95
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobMoveAgent.cs.meta11
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobPrepareAgentRaycasts.cs47
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobPrepareAgentRaycasts.cs.meta11
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobRepairPath.cs277
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobRepairPath.cs.meta11
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobStartOffMeshLinkTransition.cs33
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobStartOffMeshLinkTransition.cs.meta11
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobSyncEntitiesToTransforms.cs47
-rw-r--r--Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobSyncEntitiesToTransforms.cs.meta11
22 files changed, 1119 insertions, 0 deletions
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobAlignAgentWithMovementDirection.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobAlignAgentWithMovementDirection.cs
new file mode 100644
index 0000000..4553462
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobAlignAgentWithMovementDirection.cs
@@ -0,0 +1,43 @@
+#if MODULE_ENTITIES
+using Unity.Burst;
+using Unity.Entities;
+using Unity.Mathematics;
+using Unity.Transforms;
+
+namespace Pathfinding.ECS {
+ [BurstCompile]
+ public partial struct JobAlignAgentWithMovementDirection : IJobEntity {
+ public float dt;
+
+ public void Execute (ref LocalTransform transform, in MovementSettings movementSettings, in MovementState movementState, in AgentCylinderShape shape, in AgentMovementPlane movementPlane, in MovementControl movementControl, ref ResolvedMovement resolvedMovement) {
+ if (math.lengthsq(movementControl.targetPoint - resolvedMovement.targetPoint) > 0.001f && resolvedMovement.speed > movementSettings.follower.speed * 0.1f) {
+ // If the agent is moving, align it with the movement direction
+ var desiredDirection = movementPlane.value.ToPlane(movementControl.targetPoint - transform.Position);
+ var actualDirection = movementPlane.value.ToPlane(resolvedMovement.targetPoint - transform.Position);
+
+ float desiredAngle;
+ if (math.lengthsq(desiredDirection) > math.pow(movementSettings.follower.speed * 0.1f, 2)) {
+ desiredAngle = math.atan2(desiredDirection.y, desiredDirection.x);
+ } else {
+ // If the agent did not desire to move at all, use the agent's current rotation
+ desiredAngle = movementPlane.value.ToPlane(transform.Rotation) + math.PI*0.5f;
+ }
+
+ // The agent only moves if the actual movement direction is non-zero
+ if (math.lengthsq(actualDirection) > math.pow(movementSettings.follower.speed * 0.1f, 2)) {
+ var actualAngle = math.atan2(actualDirection.y, actualDirection.x);
+ resolvedMovement.targetRotationOffset = AstarMath.DeltaAngle(desiredAngle, actualAngle);
+ return;
+ }
+ }
+
+ {
+ // Decay the rotation offset
+ // var da = AstarMath.DeltaAngle(movementState.rotationOffset, 0);
+ // resolvedMovement.targetRotationOffset += da * dt * 2.0f;
+ resolvedMovement.targetRotationOffset = AstarMath.DeltaAngle(0, resolvedMovement.targetRotationOffset) * (1 - dt * 2.0f);
+ }
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobAlignAgentWithMovementDirection.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobAlignAgentWithMovementDirection.cs.meta
new file mode 100644
index 0000000..e8059c1
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobAlignAgentWithMovementDirection.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: b348dcdafdb36a946afe26daf64739a8
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant:
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobApplyGravity.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobApplyGravity.cs
new file mode 100644
index 0000000..347fbc9
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobApplyGravity.cs
@@ -0,0 +1,75 @@
+#if MODULE_ENTITIES
+using Pathfinding.Drawing;
+using Pathfinding.Util;
+using Unity.Burst;
+using Unity.Collections;
+using Unity.Entities;
+using Unity.Mathematics;
+using Unity.Transforms;
+using UnityEngine;
+
+namespace Pathfinding.ECS {
+ [BurstCompile]
+ public partial struct JobApplyGravity : IJobEntity {
+ [ReadOnly]
+ public NativeArray<RaycastHit> raycastHits;
+ [ReadOnly]
+ public NativeArray<RaycastCommand> raycastCommands;
+ public CommandBuilder draw;
+ public float dt;
+
+ public static void UpdateMovementPlaneFromNormal (float3 normal, ref AgentMovementPlane movementPlane) {
+ // Calculate a new movement plane that is perpendicular to the surface normal
+ // and is as similar to the previous movement plane as possible.
+ var forward = math.normalizesafe(math.mul(movementPlane.value.rotation, new float3(0, 0, 1)));
+ normal = math.normalizesafe(normal);
+ // TODO: This doesn't guarantee an orthogonal basis? forward and normal may not be perpendicular
+ movementPlane.value = new NativeMovementPlane(new quaternion(new float3x3(
+ math.cross(normal, forward),
+ normal,
+ forward
+ )));
+ }
+
+ void ResolveGravity (RaycastHit hit, bool grounded, ref LocalTransform transform, in AgentMovementPlane movementPlane, ref GravityState gravityState) {
+ var localPosition = movementPlane.value.ToPlane(transform.Position, out var currentElevation);
+ if (grounded) {
+ // Grounded
+ // Make the vertical velocity fall off exponentially. This is reasonable from a physical standpoint as characters
+ // are not completely stiff and touching the ground will not immediately negate all velocity downwards. The AI will
+ // stop moving completely due to the raycast penetration test but it will still *try* to move downwards. This helps
+ // significantly when moving down along slopes, because if the vertical velocity would be set to zero when the character
+ // was grounded it would lead to a kind of 'bouncing' behavior (try it, it's hard to explain). Ideally this should
+ // use a more physically correct formula but this is a good approximation and is much more performant. The constant
+ // CONVERGENCE_SPEED in the expression below determines how quickly it converges but high values can lead to too much noise.
+ const float CONVERGENCE_SPEED = 5f;
+ gravityState.verticalVelocity *= math.max(0, 1 - CONVERGENCE_SPEED * dt);
+
+ movementPlane.value.ToPlane(hit.point, out var hitElevation);
+ var elevationDelta = gravityState.verticalVelocity * dt;
+ const float VERTICAL_COLLISION_ADJUSTMENT_SPEED = 6f;
+ if (hitElevation > currentElevation) {
+ // Already below ground, only allow upwards movement
+ currentElevation = Mathf.MoveTowards(currentElevation, hitElevation, VERTICAL_COLLISION_ADJUSTMENT_SPEED * math.sqrt(math.abs(hitElevation - currentElevation)) * dt);
+ } else {
+ // Was above the ground, allow downwards movement until we are at the ground
+ currentElevation = math.max(hitElevation, currentElevation + elevationDelta);
+ }
+ } else {
+ var elevationDelta = gravityState.verticalVelocity * dt;
+ currentElevation += elevationDelta;
+ }
+ transform.Position = movementPlane.value.ToWorld(localPosition, currentElevation);
+ }
+
+ public void Execute (ref LocalTransform transform, in MovementSettings movementSettings, ref AgentMovementPlane movementPlane, ref GravityState gravityState, in AgentMovementPlaneSource movementPlaneSource, [Unity.Entities.EntityIndexInQuery] int entityIndexInQuery) {
+ var hit = raycastHits[entityIndexInQuery];
+ var hitAnything = math.any((float3)hit.normal != 0f);
+ if (hitAnything && movementPlaneSource.value == MovementPlaneSource.Raycast) {
+ UpdateMovementPlaneFromNormal(hit.normal, ref movementPlane);
+ }
+ ResolveGravity(hit, hitAnything, ref transform, in movementPlane, ref gravityState);
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobApplyGravity.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobApplyGravity.cs.meta
new file mode 100644
index 0000000..a53f5e1
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobApplyGravity.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: 618ca53d45ce69442aaae615eb4f3291
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant:
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobControl.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobControl.cs
new file mode 100644
index 0000000..49c804f
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobControl.cs
@@ -0,0 +1,146 @@
+#if MODULE_ENTITIES
+using Unity.Entities;
+using Unity.Mathematics;
+using Unity.Profiling;
+using Unity.Transforms;
+using Unity.Burst;
+using Unity.Collections;
+using Unity.Collections.LowLevel.Unsafe;
+using Pathfinding.Drawing;
+using Pathfinding.PID;
+using Unity.Burst.Intrinsics;
+
+namespace Pathfinding.ECS {
+ [BurstCompile]
+ public partial struct JobControl : IJobEntity, IJobEntityChunkBeginEnd {
+ public float dt;
+ public CommandBuilder draw;
+ [ReadOnly]
+ [NativeDisableContainerSafetyRestriction]
+ public NavmeshEdges.NavmeshBorderData navmeshEdgeData;
+
+ [NativeDisableContainerSafetyRestriction]
+ public NativeList<float2> edgesScratch;
+
+ private static readonly ProfilerMarker MarkerConvertObstacles = new ProfilerMarker("ConvertObstacles");
+
+ public static float3 ClampToNavmesh (float3 position, float3 closestOnNavmesh, in AgentCylinderShape shape, in AgentMovementPlane movementPlane) {
+ // Don't clamp the elevation except to make sure it's not too far below the navmesh.
+ var clamped2D = movementPlane.value.ToPlane(closestOnNavmesh, out float clampedElevation);
+ movementPlane.value.ToPlane(position, out float currentElevation);
+ currentElevation = math.max(currentElevation, clampedElevation - shape.height * 0.4f);
+ position = movementPlane.value.ToWorld(clamped2D, currentElevation);
+ return position;
+ }
+
+ public bool OnChunkBegin (in ArchetypeChunk chunk, int unfilteredChunkIndex, bool useEnabledMask, in v128 chunkEnabledMask) {
+ if (!edgesScratch.IsCreated) edgesScratch = new NativeList<float2>(64, Allocator.Temp);
+ return true;
+ }
+
+ public void OnChunkEnd (in ArchetypeChunk chunk, int unfilteredChunkIndex, bool useEnabledMask, in v128 chunkEnabledMask, bool chunkWasExecuted) {}
+
+ public void Execute (ref LocalTransform transform, ref MovementState state, in DestinationPoint destination, in AgentCylinderShape shape, in AgentMovementPlane movementPlane, in MovementSettings settings, in ResolvedMovement resolvedMovement, ref MovementControl controlOutput) {
+ // Clamp the agent to the navmesh.
+ var position = ClampToNavmesh(transform.Position, state.closestOnNavmesh, in shape, in movementPlane);
+
+ edgesScratch.Clear();
+ var scale = math.abs(transform.Scale);
+ var settingsTemp = settings.follower;
+ // Scale the settings by the agent's scale
+ settingsTemp.ScaleByAgentScale(scale);
+ settingsTemp.desiredWallDistance *= resolvedMovement.turningRadiusMultiplier;
+
+ if (state.isOnValidNode) {
+ MarkerConvertObstacles.Begin();
+ var localBounds = PIDMovement.InterestingEdgeBounds(ref settingsTemp, position, state.nextCorner, shape.height, movementPlane.value);
+ navmeshEdgeData.GetEdgesInRange(state.hierarchicalNodeIndex, localBounds, edgesScratch, movementPlane.value);
+ MarkerConvertObstacles.End();
+ }
+
+ // To ensure we detect that the end of the path is reached robustly we make the agent move slightly closer.
+ // to the destination than the stopDistance.
+ const float FUZZ = 0.005f;
+ // If we are moving towards an off-mesh link, then we want the agent to stop precisely at the off-mesh link.
+ // TODO: Depending on the link, we may want the agent to move towards the link at full speed, instead of slowing down.
+ var stopDistance = state.traversingLastPart ? math.max(0, settings.stopDistance - FUZZ) : 0f;
+ var distanceToSteeringTarget = math.max(0, state.remainingDistanceToEndOfPart - stopDistance);
+ var rotation = movementPlane.value.ToPlane(transform.Rotation) - state.rotationOffset - state.rotationOffset2;
+
+ transform.Position = position;
+
+ if (dt > 0.000001f) {
+ if (!math.isfinite(distanceToSteeringTarget)) {
+ // The agent has no path, just stay still
+ controlOutput = new MovementControl {
+ targetPoint = position,
+ speed = 0,
+ endOfPath = position,
+ maxSpeed = settings.follower.speed,
+ overrideLocalAvoidance = false,
+ hierarchicalNodeIndex = state.hierarchicalNodeIndex,
+ targetRotation = resolvedMovement.targetRotation,
+ rotationSpeed = settings.follower.maxRotationSpeed,
+ targetRotationOffset = state.rotationOffset, // May be modified by other systems
+ };
+ } else if (settings.isStopped) {
+ // The user has requested that the agent slow down as quickly as possible.
+ // TODO: If the agent is not clamped to the navmesh, it should still move towards the navmesh if it is outside it.
+ controlOutput = new MovementControl {
+ // Keep moving in the same direction as during the last frame, but slow down
+ targetPoint = position + math.normalizesafe(resolvedMovement.targetPoint - position) * 10.0f,
+ speed = settings.follower.Accelerate(resolvedMovement.speed, settings.follower.slowdownTime, -dt),
+ endOfPath = state.endOfPath,
+ maxSpeed = settings.follower.speed,
+ overrideLocalAvoidance = false,
+ hierarchicalNodeIndex = state.hierarchicalNodeIndex,
+ targetRotation = resolvedMovement.targetRotation,
+ rotationSpeed = settings.follower.maxRotationSpeed,
+ targetRotationOffset = state.rotationOffset, // May be modified by other systems
+ };
+ } else {
+ var controlParams = new PIDMovement.ControlParams {
+ edges = edgesScratch.AsArray(),
+ nextCorner = state.nextCorner,
+ agentRadius = shape.radius,
+ facingDirectionAtEndOfPath = destination.facingDirection,
+ endOfPath = state.endOfPath,
+ remainingDistance = distanceToSteeringTarget,
+ closestOnNavmesh = state.closestOnNavmesh,
+ debugFlags = settings.debugFlags,
+ p = position,
+ rotation = rotation,
+ maxDesiredWallDistance = state.followerState.maxDesiredWallDistance,
+ speed = controlOutput.speed,
+ movementPlane = movementPlane.value,
+ };
+
+ var control = PIDMovement.Control(ref settingsTemp, dt, ref controlParams, ref draw, out state.followerState.maxDesiredWallDistance);
+ var positionDelta = movementPlane.value.ToWorld(control.positionDelta, 0);
+ var speed = math.length(positionDelta) / dt;
+
+ controlOutput = new MovementControl {
+ targetPoint = position + math.normalizesafe(positionDelta) * distanceToSteeringTarget,
+ speed = speed,
+ endOfPath = state.endOfPath,
+ maxSpeed = settingsTemp.speed * 1.1f,
+ overrideLocalAvoidance = false,
+ hierarchicalNodeIndex = state.hierarchicalNodeIndex,
+ // It may seem sketchy to use a target rotation so close to the current rotation. One might think
+ // there's risk of overshooting this target rotation if the frame rate is uneven.
+ // But the TimeScaledRateManager ensures that this is not the case.
+ // The cheap simulation's time (which is the one actually rotating the agent) is always guaranteed to be
+ // behind (or precisely caught up with) the full simulation's time (that's the simulation which runs this system).
+ targetRotation = rotation + control.rotationDelta,
+ targetRotationHint = rotation + AstarMath.DeltaAngle(rotation, control.targetRotation),
+ rotationSpeed = math.abs(control.rotationDelta / dt),
+ targetRotationOffset = state.rotationOffset, // May be modified by other systems
+ };
+ }
+ } else {
+ controlOutput.hierarchicalNodeIndex = -1;
+ }
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobControl.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobControl.cs.meta
new file mode 100644
index 0000000..c4b5992
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobControl.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: 4b24028677256624696bab00b6f43ac0
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant:
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobDrawFollowerGizmos.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobDrawFollowerGizmos.cs
new file mode 100644
index 0000000..df4652d
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobDrawFollowerGizmos.cs
@@ -0,0 +1,104 @@
+#if MODULE_ENTITIES
+using System.Runtime.InteropServices;
+using Pathfinding.Drawing;
+using Pathfinding.PID;
+using Pathfinding.Util;
+using Unity.Burst;
+using Unity.Collections;
+using Unity.Collections.LowLevel.Unsafe;
+using Unity.Entities;
+using Unity.Mathematics;
+using Unity.Transforms;
+
+namespace Pathfinding.ECS {
+ [BurstCompile]
+ struct DrawGizmosJobUtils {
+ [BurstCompile]
+ internal static void DrawPath (ref CommandBuilder draw, ref UnsafeSpan<float3> vertices, ref AgentCylinderShape shape) {
+ draw.PushColor(Palette.Colorbrewer.Set1.Orange);
+ // Some people will set the agent's radius to zero. In that case we just draw the path as a polyline as we have no good reference for how to space the symbols.
+ if (shape.radius > 0.01f) {
+ var generator = new CommandBuilder.PolylineWithSymbol(CommandBuilder.SymbolDecoration.ArrowHead, shape.radius * 0.5f, shape.radius * 0.0f, shape.radius * 4f, true);
+ for (int i = vertices.Length - 1; i >= 0; i--) generator.MoveTo(ref draw, vertices[i]);
+ } else {
+ for (int i = 0; i < vertices.Length - 1; i++) draw.Line(vertices[i], vertices[i+1]);
+ }
+ draw.PopColor();
+ }
+ }
+
+ public partial struct JobDrawFollowerGizmos : IJobChunk {
+ public CommandBuilder draw;
+ public GCHandle entityManagerHandle;
+ [ReadOnly]
+ public ComponentTypeHandle<LocalTransform> LocalTransformTypeHandleRO;
+ [ReadOnly]
+ public ComponentTypeHandle<AgentCylinderShape> AgentCylinderShapeHandleRO;
+ [ReadOnly]
+ public ComponentTypeHandle<MovementSettings> MovementSettingsHandleRO;
+ [ReadOnly]
+ public ComponentTypeHandle<AgentMovementPlane> AgentMovementPlaneHandleRO;
+ // This is actually not read only, because the GetNextCorners function can modify internal state
+ // See JobRepairPath.Scheduler.ManagedStateTypeHandleRW for details about why NativeDisableContainerSafetyRestriction is required
+ [NativeDisableContainerSafetyRestriction]
+ public ComponentTypeHandle<ManagedState> ManagedStateHandleRW;
+ [ReadOnly]
+ public ComponentTypeHandle<MovementState> MovementStateHandleRO;
+ [ReadOnly]
+ public ComponentTypeHandle<ResolvedMovement> ResolvedMovementHandleRO;
+
+ [NativeDisableContainerSafetyRestriction]
+ public NativeList<float3> scratchBuffer1;
+ [NativeDisableContainerSafetyRestriction]
+ public NativeArray<int> scratchBuffer2;
+
+ public void Execute (in ArchetypeChunk chunk, int unfilteredChunkIndex, bool useEnabledMask, in Unity.Burst.Intrinsics.v128 chunkEnabledMask) {
+ if (!scratchBuffer1.IsCreated) scratchBuffer1 = new NativeList<float3>(32, Allocator.Temp);
+ if (!scratchBuffer2.IsCreated) scratchBuffer2 = new NativeArray<int>(32, Allocator.Temp);
+
+ unsafe {
+ var localTransforms = (LocalTransform*)chunk.GetNativeArray(ref LocalTransformTypeHandleRO).GetUnsafeReadOnlyPtr();
+ var agentCylinderShapes = (AgentCylinderShape*)chunk.GetNativeArray(ref AgentCylinderShapeHandleRO).GetUnsafeReadOnlyPtr();
+ var movementSettings = (MovementSettings*)chunk.GetNativeArray(ref MovementSettingsHandleRO).GetUnsafeReadOnlyPtr();
+ var movementPlanes = (AgentMovementPlane*)chunk.GetNativeArray(ref AgentMovementPlaneHandleRO).GetUnsafeReadOnlyPtr();
+ var managedStates = chunk.GetManagedComponentAccessor(ref ManagedStateHandleRW, (EntityManager)entityManagerHandle.Target);
+ var movementStates = (MovementState*)chunk.GetNativeArray(ref MovementStateHandleRO).GetUnsafeReadOnlyPtr();
+ var resolvedMovement = (ResolvedMovement*)chunk.GetNativeArray(ref ResolvedMovementHandleRO).GetUnsafeReadOnlyPtr();
+
+ for (int i = 0; i < chunk.Count; i++) {
+ Execute(ref localTransforms[i], ref movementPlanes[i], ref agentCylinderShapes[i], managedStates[i], ref movementSettings[i], ref movementStates[i], ref resolvedMovement[i]);
+ }
+ }
+ }
+
+ public void Execute (ref LocalTransform transform, ref AgentMovementPlane movementPlane, ref AgentCylinderShape shape, ManagedState managedState, ref MovementSettings settings, ref MovementState movementState, ref ResolvedMovement resolvedMovement) {
+ if ((settings.debugFlags & PIDMovement.DebugFlags.Funnel) != 0) {
+ managedState.pathTracer.DrawFunnel(draw, movementPlane.value);
+ }
+ if ((settings.debugFlags & PIDMovement.DebugFlags.Rotation) != 0) {
+ var p2D = movementPlane.value.ToPlane(transform.Position, out float positionElevation);
+ draw.PushMatrix(math.mul(new float4x4(movementPlane.value.rotation, float3.zero), float4x4.Translate(new float3(0, positionElevation, 0))));
+ var visualRotation = movementPlane.value.ToPlane(transform.Rotation);
+ var unsmoothedRotation = visualRotation - movementState.rotationOffset2;
+ var internalRotation = unsmoothedRotation - movementState.rotationOffset;
+ var targetInternalRotation = resolvedMovement.targetRotation;
+ var targetInternalRotationHint = resolvedMovement.targetRotationHint;
+ math.sincos(math.PI*0.5f + new float3(visualRotation, unsmoothedRotation, internalRotation), out var s, out var c);
+ draw.xz.ArrowheadArc(p2D, new float2(c.x, s.x), shape.radius * 1.1f, Palette.Colorbrewer.Set1.Blue);
+ draw.xz.ArrowheadArc(p2D, new float2(c.y, s.y), shape.radius * 1.1f, Palette.Colorbrewer.Set1.Purple);
+ draw.xz.ArrowheadArc(p2D, new float2(c.z, s.z), shape.radius * 1.1f, Palette.Colorbrewer.Set1.Orange);
+ math.sincos(math.PI*0.5f + new float2(targetInternalRotation, targetInternalRotationHint), out var s2, out var c2);
+ draw.xz.ArrowheadArc(p2D, new float2(c2.x, s2.x), shape.radius * 1.2f, Palette.Colorbrewer.Set1.Yellow);
+ draw.xz.ArrowheadArc(p2D, new float2(c2.y, s2.y), shape.radius * 1.2f, Palette.Colorbrewer.Set1.Pink);
+ draw.PopMatrix();
+ }
+ if ((settings.debugFlags & PIDMovement.DebugFlags.Path) != 0 && managedState.pathTracer.hasPath) {
+ scratchBuffer1.Clear();
+ managedState.pathTracer.GetNextCorners(scratchBuffer1, int.MaxValue, ref scratchBuffer2, Allocator.Temp, managedState.pathfindingSettings.traversalProvider, managedState.activePath);
+ var span = scratchBuffer1.AsUnsafeSpan();
+ DrawGizmosJobUtils.DrawPath(ref draw, ref span, ref shape);
+ }
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobDrawFollowerGizmos.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobDrawFollowerGizmos.cs.meta
new file mode 100644
index 0000000..377d6ac
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobDrawFollowerGizmos.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: f202855630112e347bc6d3e68ee6f314
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant:
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedMovementOverride.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedMovementOverride.cs
new file mode 100644
index 0000000..abdd98e
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedMovementOverride.cs
@@ -0,0 +1,45 @@
+#if MODULE_ENTITIES
+using Unity.Entities;
+using Unity.Transforms;
+
+namespace Pathfinding.ECS {
+ public partial struct JobManagedMovementOverrideBeforeControl : IJobEntity {
+ public float dt;
+
+ public void Execute (ManagedMovementOverrideBeforeControl managedOverride, Entity entity, ref LocalTransform localTransform, ref AgentCylinderShape shape, ref AgentMovementPlane movementPlane, ref DestinationPoint destination, ref MovementState movementState, ref MovementSettings movementSettings) {
+ if (managedOverride.callback != null) {
+ managedOverride.callback(entity, dt, ref localTransform, ref shape, ref movementPlane, ref destination, ref movementState, ref movementSettings);
+ // The callback may have modified the movement state, so we need to reset the path tracer version to indicate that the movement state is not up to date.
+ // This will cause the repair job to avoid optimizing some updates away.
+ movementState.pathTracerVersion--;
+ }
+ }
+ }
+
+ public partial struct JobManagedMovementOverrideAfterControl : IJobEntity {
+ public float dt;
+
+ public void Execute (ManagedMovementOverrideAfterControl managedOverride, Entity entity, ref LocalTransform localTransform, ref AgentCylinderShape shape, ref AgentMovementPlane movementPlane, ref DestinationPoint destination, ref MovementState movementState, ref MovementSettings movementSettings, ref MovementControl movementControl) {
+ if (managedOverride.callback != null) {
+ managedOverride.callback(entity, dt, ref localTransform, ref shape, ref movementPlane, ref destination, ref movementState, ref movementSettings, ref movementControl);
+ // The callback may have modified the movement state, so we need to reset the path tracer version to indicate that the movement state is not up to date.
+ // This will cause the repair job to avoid optimizing some updates away.
+ movementState.pathTracerVersion--;
+ }
+ }
+ }
+
+ public partial struct JobManagedMovementOverrideBeforeMovement : IJobEntity {
+ public float dt;
+
+ public void Execute (ManagedMovementOverrideBeforeMovement managedOverride, Entity entity, ref LocalTransform localTransform, ref AgentCylinderShape shape, ref AgentMovementPlane movementPlane, ref DestinationPoint destination, ref MovementState movementState, ref MovementSettings movementSettings, ref MovementControl movementControl, ref ResolvedMovement resolvedMovement) {
+ if (managedOverride.callback != null) {
+ managedOverride.callback(entity, dt, ref localTransform, ref shape, ref movementPlane, ref destination, ref movementState, ref movementSettings, ref movementControl, ref resolvedMovement);
+ // The callback may have modified the movement state, so we need to reset the path tracer version to indicate that the movement state is not up to date.
+ // This will cause the repair job to avoid optimizing some updates away.
+ movementState.pathTracerVersion--;
+ }
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedMovementOverride.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedMovementOverride.cs.meta
new file mode 100644
index 0000000..24d261a
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedMovementOverride.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: 6e9dcafc22a15f547984558ee0fc626f
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant:
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedOffMeshLinkTransition.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedOffMeshLinkTransition.cs
new file mode 100644
index 0000000..8055cc8
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedOffMeshLinkTransition.cs
@@ -0,0 +1,86 @@
+#pragma warning disable 0282 // Allows the 'partial' keyword without warnings
+#if MODULE_ENTITIES
+using Unity.Entities;
+using Unity.Collections;
+using UnityEngine;
+using Unity.Transforms;
+using Unity.Collections.LowLevel.Unsafe;
+
+namespace Pathfinding.ECS {
+ using Pathfinding;
+
+ public partial struct JobManagedOffMeshLinkTransition : IJobEntity {
+ public EntityCommandBuffer commandBuffer;
+ public float deltaTime;
+
+ public void Execute (Entity entity, ManagedState state, ref LocalTransform transform, ref AgentMovementPlane movementPlane, ref MovementControl movementControl, ref MovementSettings movementSettings, ref AgentOffMeshLinkTraversal linkInfo, ManagedAgentOffMeshLinkTraversal managedLinkInfo) {
+ if (!MoveNext(entity, state, ref transform, ref movementPlane, ref movementControl, ref movementSettings, ref linkInfo, managedLinkInfo, deltaTime)) {
+ commandBuffer.RemoveComponent<AgentOffMeshLinkTraversal>(entity);
+ commandBuffer.RemoveComponent<ManagedAgentOffMeshLinkTraversal>(entity);
+ }
+ }
+
+ public static bool MoveNext (Entity entity, ManagedState state, ref LocalTransform transform, ref AgentMovementPlane movementPlane, ref MovementControl movementControl, ref MovementSettings movementSettings, ref AgentOffMeshLinkTraversal linkInfo, ManagedAgentOffMeshLinkTraversal managedLinkInfo, float deltaTime) {
+ unsafe {
+ managedLinkInfo.context.SetInternalData(entity, ref transform, ref movementPlane, ref movementControl, ref movementSettings, ref linkInfo, state, deltaTime);
+ }
+
+ // Initialize the coroutine during the first step.
+ // This can also happen if the entity is duplicated, since the coroutine cannot be cloned.
+ if (managedLinkInfo.coroutine == null) {
+ // If we are calculating a path right now, cancel that path calculation.
+ // We don't want to calculate a path while we are traversing an off-mesh link.
+ state.CancelCurrentPathRequest();
+
+ if (managedLinkInfo.stateMachine == null) {
+ managedLinkInfo.stateMachine = managedLinkInfo.handler != null? managedLinkInfo.handler.GetOffMeshLinkStateMachine(managedLinkInfo.context) : null;
+ }
+ managedLinkInfo.coroutine = managedLinkInfo.stateMachine != null? managedLinkInfo.stateMachine.OnTraverseOffMeshLink(managedLinkInfo.context).GetEnumerator() : JobStartOffMeshLinkTransition.DefaultOnTraverseOffMeshLink(managedLinkInfo.context).GetEnumerator();
+ }
+
+ bool finished;
+ bool error = false;
+ bool popParts = true;
+ try {
+ finished = !managedLinkInfo.coroutine.MoveNext();
+ } catch (AgentOffMeshLinkTraversalContext.AbortOffMeshLinkTraversal) {
+ error = true;
+ finished = true;
+ popParts = false;
+ }
+ catch (System.Exception e) {
+ Debug.LogException(e, managedLinkInfo.context.gameObject);
+ // Teleport the agent to the end of the link as a fallback, if there's an exception
+ managedLinkInfo.context.Teleport(managedLinkInfo.context.link.relativeEnd);
+ finished = true;
+ error = true;
+ }
+
+ if (finished) {
+ try {
+ if (managedLinkInfo.stateMachine != null) {
+ if (error) managedLinkInfo.stateMachine.OnAbortTraversingOffMeshLink();
+ else managedLinkInfo.stateMachine.OnFinishTraversingOffMeshLink(managedLinkInfo.context);
+ }
+ } catch (System.Exception e) {
+ // If an exception happens when exiting the state machine, log it, and then continue with the cleanup
+ Debug.LogException(e, managedLinkInfo.context.gameObject);
+ }
+
+ managedLinkInfo.context.Restore();
+ if (popParts) {
+ // Pop the part leading up to the link, and the link itself
+ state.PopNextLinkFromPath();
+ }
+ }
+ return !finished;
+ }
+ }
+
+ public partial struct JobManagedOffMeshLinkTransitionCleanup : IJobEntity {
+ public void Execute (ManagedAgentOffMeshLinkTraversal managedLinkInfo) {
+ managedLinkInfo.stateMachine.OnAbortTraversingOffMeshLink();
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedOffMeshLinkTransition.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedOffMeshLinkTransition.cs.meta
new file mode 100644
index 0000000..1c23899
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobManagedOffMeshLinkTransition.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: 5a279ed93b8648d4982ea23f87877a3c
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant:
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobMoveAgent.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobMoveAgent.cs
new file mode 100644
index 0000000..331ab82
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobMoveAgent.cs
@@ -0,0 +1,95 @@
+#if MODULE_ENTITIES
+using Unity.Burst;
+using Unity.Entities;
+using Unity.Mathematics;
+using Unity.Transforms;
+
+namespace Pathfinding.ECS {
+ [BurstCompile]
+ public partial struct JobMoveAgent : IJobEntity {
+ public float dt;
+
+ static void UpdateVelocityEstimate (ref LocalTransform transform, ref MovementStatistics movementStatistics, float dt) {
+ if (dt > 0.000001f) {
+ movementStatistics.estimatedVelocity = (transform.Position - movementStatistics.lastPosition) / dt;
+ }
+ }
+
+ static void ResolveRotation (ref LocalTransform transform, ref MovementState state, in ResolvedMovement resolvedMovement, in MovementSettings movementSettings, in AgentMovementPlane movementPlane, float dt) {
+ var currentRotation = movementPlane.value.ToPlane(transform.Rotation);
+ var currentInternalRotation = currentRotation - state.rotationOffset - state.rotationOffset2;
+ var deltaRotation = math.clamp(AstarMath.DeltaAngle(currentInternalRotation, resolvedMovement.targetRotation), -resolvedMovement.rotationSpeed * dt, resolvedMovement.rotationSpeed * dt);
+ var extraRotationSpeed = math.radians(movementSettings.follower.maxRotationSpeed) * 0.5f;
+ var deltaExtraRotation = math.clamp(AstarMath.DeltaAngle(state.rotationOffset, resolvedMovement.targetRotationOffset), -extraRotationSpeed * dt, extraRotationSpeed * dt);
+ var currentUnsmoothedRotation = currentInternalRotation + state.rotationOffset;
+ var newInternalRotation = currentInternalRotation + deltaRotation;
+ // Keep track of how much extra rotation we are applying. This is done so that
+ // the movement calculation can separate this out when doing its movement calculations.
+ state.rotationOffset += deltaExtraRotation;
+ // Make sure the rotation offset is between -pi/2 and pi/2 radians
+ state.rotationOffset = AstarMath.DeltaAngle(0, state.rotationOffset);
+ var newUnsmoothedRotation = newInternalRotation + state.rotationOffset;
+
+ if (movementSettings.rotationSmoothing > 0) {
+ // Apply compensation to rotationOffset2 to precisely cancel out the agent's rotation during this frame
+ state.rotationOffset2 += currentUnsmoothedRotation - newUnsmoothedRotation;
+
+ state.rotationOffset2 = AstarMath.DeltaAngle(0, state.rotationOffset2);
+
+ // Decay the rotationOffset2. This implicitly adds an exponential moving average to the visual rotation
+ var decay = math.abs(AstarMath.DeltaAngle(currentRotation, resolvedMovement.targetRotationHint)) / movementSettings.rotationSmoothing;
+ var exponentialDecay = decay*dt;
+
+ // In addition to an exponential decay, we also add a linear decay.
+ // This is important to relatively quickly zero out the error when the agent is almost
+ // facing the right direction. With an exponential decay, it would take far too long to look good.
+ const float LINEAR_DECAY_AMOUNT = 0.1f;
+ var linearDecay = (LINEAR_DECAY_AMOUNT/movementSettings.rotationSmoothing)*dt;
+
+ if (math.abs(state.rotationOffset2) > 0) state.rotationOffset2 *= math.max(0, 1 - exponentialDecay - linearDecay/math.abs(state.rotationOffset2));
+ } else if (state.rotationOffset2 != 0) {
+ // Rotation smoothing is disabled, decay the rotation offset very quickly, but still avoid jarring changes
+ state.rotationOffset2 += math.clamp(-state.rotationOffset2, -extraRotationSpeed * dt, extraRotationSpeed * dt);
+ }
+
+ transform.Rotation = movementPlane.value.ToWorldRotation(newInternalRotation + state.rotationOffset + state.rotationOffset2);
+ }
+
+ public static float3 MoveWithoutGravity (ref LocalTransform transform, in ResolvedMovement resolvedMovement, in AgentMovementPlane movementPlane, float dt) {
+ UnityEngine.Assertions.Assert.IsTrue(math.all(math.isfinite(resolvedMovement.targetPoint)));
+ // Move only along the movement plane
+ var localDir = movementPlane.value.ToPlane(resolvedMovement.targetPoint - transform.Position);
+ var magn = math.length(localDir);
+ var localDelta = math.select(localDir, localDir * math.clamp(resolvedMovement.speed * dt / magn, 0, 1.0f), magn > 0.0001f);
+ var delta = movementPlane.value.ToWorld(localDelta, 0);
+ return delta;
+ }
+
+ public static void ResolvePositionSmoothing (float3 movementDelta, ref MovementState state, in MovementSettings movementSettings, float dt) {
+ if (movementSettings.positionSmoothing > 0) {
+ state.positionOffset -= movementDelta;
+ var exponentialDecay = 1f/movementSettings.positionSmoothing*dt;
+ var linearDecay = 0.1f/movementSettings.positionSmoothing*dt;
+ var positionOffsetMagnitude = math.length(state.positionOffset);
+ if (positionOffsetMagnitude > 0) state.positionOffset *= math.max(0, 1 - exponentialDecay - linearDecay/positionOffsetMagnitude);
+ } else {
+ state.positionOffset = float3.zero;
+ }
+ }
+
+ public void Execute (ref LocalTransform transform, in AgentCylinderShape shape, in AgentMovementPlane movementPlane, ref MovementState state, in MovementSettings movementSettings, in ResolvedMovement resolvedMovement, ref MovementStatistics movementStatistics) {
+ MoveAgent(ref transform, in shape, in movementPlane, ref state, in movementSettings, in resolvedMovement, ref movementStatistics, dt);
+ }
+
+ public static void MoveAgent (ref LocalTransform transform, in AgentCylinderShape shape, in AgentMovementPlane movementPlane, ref MovementState state, in MovementSettings movementSettings, in ResolvedMovement resolvedMovement, ref MovementStatistics movementStatistics, float dt) {
+ var delta = MoveWithoutGravity(ref transform, in resolvedMovement, in movementPlane, dt);
+ UnityEngine.Assertions.Assert.IsTrue(math.all(math.isfinite(delta)), "Refusing to set the agent's position to a non-finite vector");
+ transform.Position += delta;
+ ResolvePositionSmoothing(delta, ref state, in movementSettings, dt);
+ ResolveRotation(ref transform, ref state, in resolvedMovement, in movementSettings, in movementPlane, dt);
+ UpdateVelocityEstimate(ref transform, ref movementStatistics, dt);
+ movementStatistics.lastPosition = transform.Position;
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobMoveAgent.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobMoveAgent.cs.meta
new file mode 100644
index 0000000..c989a0d
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobMoveAgent.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: ae237f49f264df546bb908b1d4f3d658
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant:
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobPrepareAgentRaycasts.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobPrepareAgentRaycasts.cs
new file mode 100644
index 0000000..c6c4081
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobPrepareAgentRaycasts.cs
@@ -0,0 +1,47 @@
+#if MODULE_ENTITIES
+using Pathfinding.Drawing;
+using Unity.Burst;
+using Unity.Collections;
+using Unity.Entities;
+using Unity.Mathematics;
+using Unity.Transforms;
+using UnityEngine;
+
+namespace Pathfinding.ECS {
+ [BurstCompile]
+ public partial struct JobPrepareAgentRaycasts : IJobEntity {
+ public NativeArray<RaycastCommand> raycastCommands;
+ public QueryParameters raycastQueryParameters;
+ public CommandBuilder draw;
+ public float dt;
+ public float gravity;
+
+ void ApplyGravity (ref GravityState gravityState) {
+ gravityState.verticalVelocity += gravity * dt;
+ }
+
+ RaycastCommand CalculateRaycastCommands (ref LocalTransform transform, in AgentCylinderShape shape, in AgentMovementPlane movementPlane, in MovementSettings movementSettings, ref GravityState gravityState) {
+ // TODO: Might be more performant to convert the movement plane to two matrices
+
+ movementPlane.value.ToPlane(transform.Position, out var lastElevation);
+
+ var elevationDelta = gravityState.verticalVelocity * dt;
+ var localPosition = movementPlane.value.ToPlane(transform.Position, out var elevation);
+ var rayStartElevation = math.max(elevation + elevationDelta, lastElevation) + shape.height * 0.5f;
+ var rayStopElevation = math.min(elevation + elevationDelta, lastElevation);
+ float rayLength = rayStartElevation - rayStopElevation; // TODO: Multiply by scale
+ var down = movementPlane.value.ToWorld(0, -1);
+ raycastQueryParameters.layerMask = movementSettings.groundMask;
+ return new RaycastCommand(movementPlane.value.ToWorld(localPosition, rayStartElevation), down, raycastQueryParameters, rayLength);
+ }
+
+ public void Execute (ref LocalTransform transform, in AgentCylinderShape shape, in AgentMovementPlane movementPlane, ref MovementState state, in MovementSettings movementSettings, ref ResolvedMovement resolvedMovement, ref MovementStatistics movementStatistics, ref GravityState gravityState, [Unity.Entities.EntityIndexInQuery] int entityIndexInQuery) {
+ // Move only along the movement plane
+ // JobMoveAgent.MoveAgent(ref transform, in shape, in movementPlane, ref state, in movementSettings, in resolvedMovement, ref movementStatistics, dt);
+
+ ApplyGravity(ref gravityState);
+ raycastCommands[entityIndexInQuery] = CalculateRaycastCommands(ref transform, in shape, in movementPlane, in movementSettings, ref gravityState);
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobPrepareAgentRaycasts.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobPrepareAgentRaycasts.cs.meta
new file mode 100644
index 0000000..7d0a011
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobPrepareAgentRaycasts.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: 9de01002f503a3e4abd6467cd6de7a44
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant:
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobRepairPath.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobRepairPath.cs
new file mode 100644
index 0000000..7f0e193
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobRepairPath.cs
@@ -0,0 +1,277 @@
+#if MODULE_ENTITIES
+using Unity.Entities;
+using Unity.Mathematics;
+using Unity.Profiling;
+using Unity.Transforms;
+using Unity.Collections;
+using Unity.Collections.LowLevel.Unsafe;
+using GCHandle = System.Runtime.InteropServices.GCHandle;
+
+namespace Pathfinding.ECS {
+ using Pathfinding;
+ using Pathfinding.Util;
+ using Unity.Burst;
+ using Unity.Jobs;
+
+ /// <summary>
+ /// Repairs the path of agents.
+ ///
+ /// This job will repair the agent's path based on the agent's current position and its destination.
+ /// It will also recalculate various statistics like how far the agent is from the destination,
+ /// and if it has reached the destination or not.
+ /// </summary>
+ public struct JobRepairPath : IJobChunk {
+ public struct Scheduler {
+ [ReadOnly]
+ public ComponentTypeHandle<LocalTransform> LocalTransformTypeHandleRO;
+ public ComponentTypeHandle<MovementState> MovementStateTypeHandleRW;
+ [ReadOnly]
+ public ComponentTypeHandle<AgentCylinderShape> AgentCylinderShapeTypeHandleRO;
+ // NativeDisableContainerSafetyRestriction seems to be necessary because otherwise we will get an error:
+ // "The ComponentTypeHandle<Pathfinding.ECS.ManagedState> ... can not be accessed. Nested native containers are illegal in jobs."
+ // However, Unity doesn't seem to check for this at all times. Currently, I can only replicate the error if DoTween Pro is also installed.
+ // I have no idea how this unrelated package influences unity to actually do the check.
+ // We know it is safe to access the managed state because we make sure to never access an entity from multiple threads at the same time.
+ [NativeDisableContainerSafetyRestriction]
+ public ComponentTypeHandle<ManagedState> ManagedStateTypeHandleRW;
+ [ReadOnly]
+ public ComponentTypeHandle<MovementSettings> MovementSettingsTypeHandleRO;
+ [ReadOnly]
+ public ComponentTypeHandle<DestinationPoint> DestinationPointTypeHandleRO;
+ [ReadOnly]
+ public ComponentTypeHandle<AgentMovementPlane> AgentMovementPlaneTypeHandleRO;
+ public ComponentTypeHandle<ReadyToTraverseOffMeshLink> ReadyToTraverseOffMeshLinkTypeHandleRW;
+ public GCHandle entityManagerHandle;
+ public bool onlyApplyPendingPaths;
+
+ public EntityQueryBuilder GetEntityQuery (Allocator allocator) {
+ return new EntityQueryBuilder(Allocator.Temp)
+ .WithAllRW<MovementState>()
+ .WithAllRW<ManagedState>()
+ .WithAllRW<LocalTransform>()
+ .WithAll<MovementSettings, DestinationPoint, AgentMovementPlane, AgentCylinderShape>()
+ // .WithAny<ReadyToTraverseOffMeshLink>() // TODO: Use WithPresent in newer versions
+ .WithAbsent<AgentOffMeshLinkTraversal>();
+ }
+
+ public Scheduler(ref SystemState systemState) {
+ entityManagerHandle = GCHandle.Alloc(systemState.EntityManager);
+ LocalTransformTypeHandleRO = systemState.GetComponentTypeHandle<LocalTransform>(true);
+ MovementStateTypeHandleRW = systemState.GetComponentTypeHandle<MovementState>(false);
+ AgentCylinderShapeTypeHandleRO = systemState.GetComponentTypeHandle<AgentCylinderShape>(true);
+ DestinationPointTypeHandleRO = systemState.GetComponentTypeHandle<DestinationPoint>(true);
+ AgentMovementPlaneTypeHandleRO = systemState.GetComponentTypeHandle<AgentMovementPlane>(true);
+ MovementSettingsTypeHandleRO = systemState.GetComponentTypeHandle<MovementSettings>(true);
+ ReadyToTraverseOffMeshLinkTypeHandleRW = systemState.GetComponentTypeHandle<ReadyToTraverseOffMeshLink>(false);
+ // Need to bypass the T : unmanaged check in systemState.GetComponentTypeHandle
+ ManagedStateTypeHandleRW = systemState.EntityManager.GetComponentTypeHandle<ManagedState>(false);
+ onlyApplyPendingPaths = false;
+ }
+
+ public void Dispose () {
+ entityManagerHandle.Free();
+ }
+
+ void Update (ref SystemState systemState) {
+ LocalTransformTypeHandleRO.Update(ref systemState);
+ MovementStateTypeHandleRW.Update(ref systemState);
+ AgentCylinderShapeTypeHandleRO.Update(ref systemState);
+ DestinationPointTypeHandleRO.Update(ref systemState);
+ ManagedStateTypeHandleRW.Update(ref systemState);
+ MovementSettingsTypeHandleRO.Update(ref systemState);
+ AgentMovementPlaneTypeHandleRO.Update(ref systemState);
+ ReadyToTraverseOffMeshLinkTypeHandleRW.Update(ref systemState);
+ }
+
+ public JobHandle ScheduleParallel (ref SystemState systemState, EntityQuery query, JobHandle dependency) {
+ Update(ref systemState);
+ return new JobRepairPath {
+ scheduler = this,
+ onlyApplyPendingPaths = onlyApplyPendingPaths
+ }.ScheduleParallel(query, dependency);
+ }
+ }
+
+ public Scheduler scheduler;
+
+ [NativeDisableContainerSafetyRestriction]
+ public NativeArray<int> indicesScratch;
+ [NativeDisableContainerSafetyRestriction]
+ public NativeList<float3> nextCornersScratch;
+ public bool onlyApplyPendingPaths;
+
+
+ public void Execute (in ArchetypeChunk chunk, int unfilteredChunkIndex, bool useEnabledMask, in Unity.Burst.Intrinsics.v128 chunkEnabledMask) {
+ if (!indicesScratch.IsCreated) {
+ nextCornersScratch = new NativeList<float3>(Allocator.Temp);
+ indicesScratch = new NativeArray<int>(8, Allocator.Temp);
+ }
+
+ unsafe {
+ var localTransforms = (LocalTransform*)chunk.GetNativeArray(ref scheduler.LocalTransformTypeHandleRO).GetUnsafeReadOnlyPtr();
+ var movementStates = (MovementState*)chunk.GetNativeArray(ref scheduler.MovementStateTypeHandleRW).GetUnsafePtr();
+ var agentCylinderShapes = (AgentCylinderShape*)chunk.GetNativeArray(ref scheduler.AgentCylinderShapeTypeHandleRO).GetUnsafeReadOnlyPtr();
+ var destinationPoints = (DestinationPoint*)chunk.GetNativeArray(ref scheduler.DestinationPointTypeHandleRO).GetUnsafeReadOnlyPtr();
+ var movementSettings = (MovementSettings*)chunk.GetNativeArray(ref scheduler.MovementSettingsTypeHandleRO).GetUnsafeReadOnlyPtr();
+ var agentMovementPlanes = (AgentMovementPlane*)chunk.GetNativeArray(ref scheduler.AgentMovementPlaneTypeHandleRO).GetUnsafeReadOnlyPtr();
+ var mask = chunk.GetEnabledMask(ref scheduler.ReadyToTraverseOffMeshLinkTypeHandleRW);
+
+ var managedStates = chunk.GetManagedComponentAccessor(ref scheduler.ManagedStateTypeHandleRW, (EntityManager)scheduler.entityManagerHandle.Target);
+
+ for (int i = 0; i < chunk.Count; i++) {
+ Execute(
+ ref localTransforms[i],
+ ref movementStates[i],
+ ref agentCylinderShapes[i],
+ ref agentMovementPlanes[i],
+ ref destinationPoints[i],
+ mask.GetEnabledRefRW<ReadyToTraverseOffMeshLink>(i),
+ managedStates[i],
+ in movementSettings[i],
+ nextCornersScratch,
+ ref indicesScratch,
+ Allocator.Temp,
+ onlyApplyPendingPaths
+ );
+ }
+ }
+ }
+
+ private static readonly ProfilerMarker MarkerRepair = new ProfilerMarker("Repair");
+ private static readonly ProfilerMarker MarkerGetNextCorners = new ProfilerMarker("GetNextCorners");
+ private static readonly ProfilerMarker MarkerUpdateReachedEndInfo = new ProfilerMarker("UpdateReachedEndInfo");
+
+ public static void Execute (ref LocalTransform transform, ref MovementState state, ref AgentCylinderShape shape, ref AgentMovementPlane movementPlane, ref DestinationPoint destination, EnabledRefRW<ReadyToTraverseOffMeshLink> readyToTraverseOffMeshLink, ManagedState managedState, in MovementSettings settings, NativeList<float3> nextCornersScratch, ref NativeArray<int> indicesScratch, Allocator allocator, bool onlyApplyPendingPaths) {
+ // Only enabled by the PollPendingPathsSystem
+ if (onlyApplyPendingPaths) {
+ if (managedState.pendingPath != null && managedState.pendingPath.IsDone()) {
+ // The path has been calculated, apply it to the agent
+ // Immediately after this we must also repair the path to ensure that it is valid and that
+ // all properties like #MovementState.reachedEndOfPath are correct.
+ ManagedState.SetPath(managedState.pendingPath, managedState, in movementPlane, ref destination);
+ } else {
+ // The agent has no path that has just been calculated, skip it
+ return;
+ }
+ }
+
+ ref var pathTracer = ref managedState.pathTracer;
+
+ if (pathTracer.hasPath) {
+ MarkerRepair.Begin();
+ // Update the start and end points of the path based on the current position and destination.
+ // This will repair the path if necessary, ensuring that the agent has a valid, if not necessarily optimal, path.
+ // If it cannot be repaired well, the path will be marked as stale.
+ state.closestOnNavmesh = pathTracer.UpdateStart(transform.Position, PathTracer.RepairQuality.High, movementPlane.value, managedState.pathfindingSettings.traversalProvider, managedState.activePath);
+ state.endOfPath = pathTracer.UpdateEnd(destination.destination, PathTracer.RepairQuality.High, movementPlane.value, managedState.pathfindingSettings.traversalProvider, managedState.activePath);
+ MarkerRepair.End();
+
+ if (state.pathTracerVersion != pathTracer.version) {
+ nextCornersScratch.Clear();
+
+ MarkerGetNextCorners.Begin();
+ // Find the next corners of the path. The first corner is our current position,
+ // the second corner is the one we are moving towards and the third corner is the one after that.
+ //
+ // Using GetNextCorners with the default transformation instead of ConvertCornerIndicesToPathProjected
+ // is about 20% faster, but it does not work well at all on spherical worlds.
+ // In the future we might want to switch dynamically between these modes,
+ // but on the other hand, it is very nice to be able to use the exact same code path for everything.
+ // pathTracer.GetNextCorners(nextCornersScratch, 3, ref indicesScratch, allocator);
+ var numCorners = pathTracer.GetNextCornerIndices(ref indicesScratch, pathTracer.desiredCornersForGoodSimplification, allocator, out bool lastCorner, managedState.pathfindingSettings.traversalProvider, managedState.activePath);
+ pathTracer.ConvertCornerIndicesToPathProjected(indicesScratch, numCorners, lastCorner, nextCornersScratch, movementPlane.value.up);
+ MarkerGetNextCorners.End();
+
+ // We need to copy a few fields to a new struct, in order to be able to pass it to a burstified function
+ var pathTracerInfo = new JobRepairPathHelpers.PathTracerInfo {
+ endPointOfFirstPart = pathTracer.endPointOfFirstPart,
+ partCount = pathTracer.partCount,
+ isStale = pathTracer.isStale
+ };
+ var nextCorners = nextCornersScratch.AsUnsafeSpan();
+ JobRepairPathHelpers.UpdateReachedEndInfo(ref nextCorners, ref state, ref movementPlane, ref transform, ref shape, ref destination, settings.stopDistance, ref pathTracerInfo);
+ state.pathTracerVersion = pathTracer.version;
+ } else {
+ JobRepairPathHelpers.UpdateReachedOrientation(ref state, ref transform, ref movementPlane, ref destination);
+ }
+
+ if (pathTracer.startNode != null && !pathTracer.startNode.Destroyed && pathTracer.startNode.Walkable) {
+ state.graphIndex = pathTracer.startNode.GraphIndex;
+ state.hierarchicalNodeIndex = pathTracer.startNode.HierarchicalNodeIndex;
+ } else {
+ state.graphIndex = GraphNode.InvalidGraphIndex;
+ state.hierarchicalNodeIndex = -1;
+ }
+ } else {
+ state.SetPathIsEmpty(transform.Position);
+ }
+
+ if (readyToTraverseOffMeshLink.IsValid) readyToTraverseOffMeshLink.ValueRW = state.reachedEndOfPart && managedState.pathTracer.isNextPartValidLink;
+ }
+ }
+
+ [BurstCompile]
+ static class JobRepairPathHelpers {
+ public struct PathTracerInfo {
+ public float3 endPointOfFirstPart;
+ public int partCount;
+ // Bools are not blittable by burst so we must use a byte instead. Very ugly, but it is what it is.
+ byte isStaleBacking;
+ public bool isStale {
+ get => isStaleBacking != 0;
+ set => isStaleBacking = value ? (byte)1 : (byte)0;
+ }
+ }
+
+ /// <summary>Checks if the agent has reached its destination, or the end of the path</summary>
+ [BurstCompile]
+ public static void UpdateReachedEndInfo (ref UnsafeSpan<float3> nextCorners, ref MovementState state, ref AgentMovementPlane movementPlane, ref LocalTransform transform, ref AgentCylinderShape shape, ref DestinationPoint destination, float stopDistance, ref PathTracerInfo pathTracer) {
+ // TODO: Edit GetNextCorners so that it gets corners until at least stopDistance units from the agent
+ state.nextCorner = nextCorners.length > 1 ? nextCorners[1] : transform.Position;
+ state.remainingDistanceToEndOfPart = PathTracer.RemainingDistanceLowerBound(in nextCorners, in pathTracer.endPointOfFirstPart, in movementPlane.value);
+
+ // TODO: Check if end node is the globally closest node
+ movementPlane.value.ToPlane(pathTracer.endPointOfFirstPart - transform.Position, out var elevationDiffEndOfPart);
+ var validHeightRangeEndOfPart = elevationDiffEndOfPart< shape.height && elevationDiffEndOfPart > -0.5f*shape.height;
+
+ movementPlane.value.ToPlane(destination.destination - transform.Position, out var elevationDiffDestination);
+ var validHeightRangeDestination = elevationDiffDestination< shape.height && elevationDiffDestination > -0.5f*shape.height;
+ var endOfPathToDestination = math.length(movementPlane.value.ToPlane(destination.destination - state.endOfPath));
+ // If reachedEndOfPath is true we allow a slightly larger margin of error for reachedDestination.
+ // This is to ensure that if reachedEndOfPath becomes true, it is very likely that reachedDestination becomes
+ // true during the same frame.
+ const float FUZZ = 0.01f;
+ // When checking if the agent has reached the end of the current part (mostly used for off-mesh-links), we check against
+ // the agent's radius. This is because when there are many agents trying to reach the same off-mesh-link, the agents will
+ // crowd up and it may become hard to get to a point closer than the agent's radius.
+ state.reachedEndOfPart = !pathTracer.isStale && validHeightRangeEndOfPart && state.remainingDistanceToEndOfPart <= shape.radius*1.1f;
+ state.reachedEndOfPath = !pathTracer.isStale && validHeightRangeEndOfPart && pathTracer.partCount == 1 && state.remainingDistanceToEndOfPart <= stopDistance;
+ state.reachedDestination = !pathTracer.isStale && validHeightRangeDestination && pathTracer.partCount == 1 && state.remainingDistanceToEndOfPart + endOfPathToDestination <= stopDistance + (state.reachedEndOfPath ? FUZZ : 0);
+ state.traversingLastPart = pathTracer.partCount == 1;
+ UpdateReachedOrientation(ref state, ref transform, ref movementPlane, ref destination);
+ }
+
+ /// <summary>Checks if the agent is oriented towards the desired facing direction</summary>
+ public static void UpdateReachedOrientation (ref MovementState state, ref LocalTransform transform, ref AgentMovementPlane movementPlane, ref DestinationPoint destination) {
+ state.reachedEndOfPathAndOrientation = state.reachedEndOfPath;
+ state.reachedDestinationAndOrientation = state.reachedDestination;
+ if (state.reachedEndOfPathAndOrientation || state.reachedDestinationAndOrientation) {
+ var reachedOrientation = ReachedDesiredOrientation(ref transform, ref movementPlane, ref destination);
+ state.reachedEndOfPathAndOrientation &= reachedOrientation;
+ state.reachedDestinationAndOrientation &= reachedOrientation;
+ }
+ }
+
+ static bool ReachedDesiredOrientation (ref LocalTransform transform, ref AgentMovementPlane movementPlane, ref DestinationPoint destination) {
+ var facingDirection2D = math.normalizesafe(movementPlane.value.ToPlane(destination.facingDirection));
+
+ // If no desired facing direction is set, then we always treat the orientation as correct
+ if (math.all(facingDirection2D == 0)) return true;
+
+ var forward2D = math.normalizesafe(movementPlane.value.ToPlane(transform.Forward()));
+ const float ANGLE_THRESHOLD_COS = 0.9999f;
+ return math.dot(forward2D, facingDirection2D) >= ANGLE_THRESHOLD_COS;
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobRepairPath.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobRepairPath.cs.meta
new file mode 100644
index 0000000..d1ba13b
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobRepairPath.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: db3650f148245bf4ba822d172a34cc65
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant:
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobStartOffMeshLinkTransition.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobStartOffMeshLinkTransition.cs
new file mode 100644
index 0000000..994c68d
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobStartOffMeshLinkTransition.cs
@@ -0,0 +1,33 @@
+#pragma warning disable 0282 // Allows the 'partial' keyword without warnings
+#if MODULE_ENTITIES
+using Unity.Entities;
+using Unity.Mathematics;
+
+namespace Pathfinding.ECS {
+ public partial struct JobStartOffMeshLinkTransition {
+ public EntityCommandBuffer commandBuffer;
+
+ /// <summary>
+ /// This is a fallback for traversing off-mesh links in case the user has not specified a custom traversal method.
+ /// It is a coroutine which will move the agent from the start point of the link to the end point of the link.
+ /// It will also disable RVO for the agent while traversing the link.
+ /// </summary>
+ public static System.Collections.Generic.IEnumerable<object> DefaultOnTraverseOffMeshLink (AgentOffMeshLinkTraversalContext ctx) {
+ var linkInfo = ctx.link;
+ var up = ctx.movementPlane.ToWorld(float2.zero, 1);
+ var dirInPlane = ctx.movementPlane.ToWorld(ctx.movementPlane.ToPlane(linkInfo.relativeEnd - linkInfo.relativeStart), 0);
+ var rot = quaternion.LookRotationSafe(dirInPlane, up);
+
+ while (!ctx.MoveTowards(linkInfo.relativeStart, rot, true, false).reached) yield return null;
+
+ ctx.DisableLocalAvoidance();
+
+ while (!ctx.MoveTowards(linkInfo.relativeEnd, rot, true, false).reached) yield return null;
+
+ // ctx.Teleport(linkInfo.endPoint);
+
+ yield break;
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobStartOffMeshLinkTransition.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobStartOffMeshLinkTransition.cs.meta
new file mode 100644
index 0000000..69baaa9
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobStartOffMeshLinkTransition.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: fee7292c827674f4eb6ef066b3fd1c99
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant:
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobSyncEntitiesToTransforms.cs b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobSyncEntitiesToTransforms.cs
new file mode 100644
index 0000000..041f03d
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobSyncEntitiesToTransforms.cs
@@ -0,0 +1,47 @@
+#if MODULE_ENTITIES
+using Unity.Burst;
+using Unity.Collections;
+using Unity.Entities;
+using Unity.Mathematics;
+using Unity.Transforms;
+using UnityEngine.Jobs;
+
+namespace Pathfinding.ECS {
+ [BurstCompile]
+ struct JobSyncEntitiesToTransforms : IJobParallelForTransform {
+ [ReadOnly]
+ public NativeArray<Entity> entities;
+ [ReadOnly]
+ public ComponentLookup<LocalTransform> entityPositions;
+ [ReadOnly]
+ public ComponentLookup<MovementState> movementState;
+ [ReadOnly]
+ public ComponentLookup<SyncPositionWithTransform> syncPositionWithTransform;
+ [ReadOnly]
+ public ComponentLookup<SyncRotationWithTransform> syncRotationWithTransform;
+ [ReadOnly]
+ public ComponentLookup<OrientationYAxisForward> orientationYAxisForward;
+
+ public void Execute (int index, TransformAccess transform) {
+ var entity = entities[index];
+ if (!entityPositions.HasComponent(entity)) return;
+ float3 offset = float3.zero;
+ if (movementState.TryGetComponent(entity, out var ms)) {
+ offset = ms.positionOffset;
+ }
+
+ var tr = entityPositions.GetRefRO(entity);
+ if (syncPositionWithTransform.HasComponent(entity)) transform.position = tr.ValueRO.Position + offset;
+ if (syncRotationWithTransform.HasComponent(entity)) {
+ if (orientationYAxisForward.HasComponent(entity)) {
+ // Y axis forward
+ transform.rotation = math.mul(tr.ValueRO.Rotation, SyncTransformsToEntitiesSystem.ZAxisForwardToYAxisForward);
+ } else {
+ // Z axis forward
+ transform.rotation = tr.ValueRO.Rotation;
+ }
+ }
+ }
+ }
+}
+#endif
diff --git a/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobSyncEntitiesToTransforms.cs.meta b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobSyncEntitiesToTransforms.cs.meta
new file mode 100644
index 0000000..8edba2e
--- /dev/null
+++ b/Other/AstarPathfindingDemo/Packages/com.arongranberg.astar/Core/ECS/Jobs/JobSyncEntitiesToTransforms.cs.meta
@@ -0,0 +1,11 @@
+fileFormatVersion: 2
+guid: bbb93f3ffd0760d4e9b68f4376e30aeb
+MonoImporter:
+ externalObjects: {}
+ serializedVersion: 2
+ defaultReferences: []
+ executionOrder: 0
+ icon: {instanceID: 0}
+ userData:
+ assetBundleName:
+ assetBundleVariant: