You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Hi, I found that waypoints calculation at long distances are way too inaccurate and also costly.
There is exact calculation of waypoints without "accuracy" tuning. Too busy to create a proper pull request, so here is the code:
privatestaticList<ReedSheppPathfindingCar>AddWaypoints(PathWordsword,PathSegmentLengthspathSegmentLengths,ReedSheppPathfindingCarcarStart,ReedSheppPathfindingCarcarEnd,floatwpDistance,floatturningRadius,boolgenerateOneWp){// Find the car settings we need to drive through the pathList<SegmentSettings>pathSettings= PathSettings.GetSettings(word, pathSegmentLengths);// Each segment starts from the second subsegment to prevent waypoints duplication. So, we need to add first waypoint manuallyList<ReedSheppPathfindingCar>waypoints=newList<ReedSheppPathfindingCar>();
waypoints.Add(new ReedSheppPathfindingCar(carStart.Position, carStart.HeadingInRad, pathSettings[0].Gear, pathSettings[0].Steering));// Track last waypointReedSheppPathfindingCarlastWaypoint= waypoints[^1];// Loop through all 3-5 path segmentsforeach(SegmentSettings segmentSettings in pathSettings){intsubSegments=(int)Math.Ceiling(segmentSettings.Length *turningRadius/wpDistance);floatinterpolationPerSubsegment=wpDistance/(segmentSettings.Length *turningRadius);Vector3segmentStartPosition= lastWaypoint.Position;floatsegmentStartHeading= lastWaypoint.HeadingInRad;if(segmentSettings.Steering == ReedSheppPathfindingCar.Steering.Straight){floatdirection= segmentSettings.Gear == ReedSheppPathfindingCar.Gear.Back ?-1f:1f;Vector3delta=direction* segmentSettings.Length *turningRadius*new Vector3(Mathf.Sin(segmentStartHeading),0f, Mathf.Cos(segmentStartHeading));Vector3segmentEndPosition=segmentStartPosition+delta;for(inti=1;i <= subSegments;i++){floatinterpolation= Mathf.Clamp01(i*interpolationPerSubsegment);Vector3position= Vector3.Lerp(segmentStartPosition, segmentEndPosition, interpolation);
waypoints.Add(new ReedSheppPathfindingCar(position, segmentStartHeading, segmentSettings.Gear, segmentSettings.Steering));if(generateOneWp){returnwaypoints;}}}else{floatreverseIfLeft= segmentSettings.Steering == ReedSheppPathfindingCar.Steering.Left ?-1f:1f;floatreverseIfBack= segmentSettings.Gear == ReedSheppPathfindingCar.Gear.Back ?-1f:1f;floatsteeringClockwise=reverseIfLeft*reverseIfBack;floatsteeringAngle= segmentSettings.Length *steeringClockwise;floatdisplacementAngle=segmentStartHeading+ Mathf.PI /2f*reverseIfLeft;Vector3displacement=new Vector3(Mathf.Sin(displacementAngle),0f, Mathf.Cos(displacementAngle));for(inti=1;i <= subSegments;i++){floatinterpolation= Mathf.Clamp01(i*interpolationPerSubsegment);floatcurrentSteering=steeringAngle*interpolation;floatcircleAngle=segmentStartHeading- Mathf.PI /2f*reverseIfLeft+currentSteering;Vector3circle=new Vector3(Mathf.Sin(circleAngle),0f, Mathf.Cos(circleAngle));Vector3delta=(circle+displacement)*turningRadius;Vector3position=segmentStartPosition+delta;floatheading=segmentStartHeading+currentSteering;
waypoints.Add(new ReedSheppPathfindingCar(position, heading, segmentSettings.Gear, segmentSettings.Steering));if(generateOneWp){returnwaypoints;}}}lastWaypoint= waypoints[^1];}// The accuracy of the last waypoint is about 1.E-5 for the position and 1.E-7 for the angle.// So, there no need for a correction, but better be safe then sorry.
waypoints[^1]=new ReedSheppPathfindingCar(carEnd.Position, carEnd.HeadingInRad, lastWaypoint.CurrentGear, lastWaypoint.CurrentSteering);returnwaypoints;}
The text was updated successfully, but these errors were encountered:
Hi, I found that waypoints calculation at long distances are way too inaccurate and also costly.
There is exact calculation of waypoints without "accuracy" tuning. Too busy to create a proper pull request, so here is the code:
The text was updated successfully, but these errors were encountered: