Angular Velocity Adjustment

Fairly certain that this is not a bug, but a preference between the larger and smaller tractor settings. I’ve tricked AOG many times by extending the wheel base to allow the tractor to turn sharper. Common sense tells me this is wrong. The longer the wheel base the larger the turn radius. I do understand why making the wheel base larger helps it turn, it is because the angular velocity was being exceeded so it would limit the steer angle.

I’ve been looking at the angular velocity calculations in the code. It has always seemed high to me. Today, I built a label that I could diagnose what I was seeing. I started with first calculating the radius of the circle that it was turning based on the steer angle. Verified that this “looked right.” Then went into circumference. If I divided this by speed, it would give me the time to turn the full circle. On to radians per second (angular velocity). The code is set to a default setting of 7 radians/sec. That should be a gracious plenty. Over one full circle in a second. However, the code is calculating near this on the smallest turns.

I then built an excel sheet and compared what I was seeing with the AOG values and an online calculator. When I was satisfied that the excel sheet was correct, and timing the full circle as accurate as the clicks on my watch, I wrote out the formula and started canceling terms.
Down to Av=V/R .
V = velocity (m/s) = pn.speed1000/36000 or pn.speed0.277777
R = Radius (meters). =
((mf.vehicle.wheelbase) / ((Math.Tan(glm.toRadians(steerAngle)))) ± (mf.vehicle.trackWidth / 2))

After thinking that it could not be that simple, I found the same formula on Google.

Saying all of this, I think (And I could be way off) that the angular velocity formulas through out the code are heavy by (2*pi). I removed them and found it to drive the U-turns much cleaner. It followed the curves closer. It did take some setting adjustments, but if followed it much cleaner.

That being said, the max steer angle would control the radius, so there are limits. Also, I can’t find how to adjust the saved angular velocity. I tried but, could not get it to stick. Seemed to reload the default 7. 7 is too high.

This may be of use to some of the smaller tractor people out here.

Below is what the ABline one looks like. Also note, when setting the steerAngleAB, I added in one half of the track width. And using the Sin of the Steerangle is even a little closer.

Someone with more smarts than myself need to check this. If you find that all of this that I’ve stated is incorrect, and it was written that way for other reasons, we can gladly delete this post. As a simple check to follow, have the console write out the angle in the YouTurn.cs and compare it to how fast you are turning. Anything greater than PI/2 (1.57) is turning 90 degrees every second (full U-turn in 2 seconds.)

               steerAngleAB = glm.toDegrees(Math.Atan(2 * (((goalPointAB.easting - pivot.easting) * Math.Cos(localHeading))
                    + ((goalPointAB.northing - pivot.northing) * Math.Sin(localHeading))) * (mf.vehicle.wheelbase + (mf.vehicle.trackWidth / 2))
                    / goalPointDistanceDSquared));
                if (steerAngleAB < -mf.vehicle.maxSteerAngle) steerAngleAB = -mf.vehicle.maxSteerAngle;
                if (steerAngleAB > mf.vehicle.maxSteerAngle) steerAngleAB = mf.vehicle.maxSteerAngle;

                //limit circle size for display purpose
                if (ppRadiusAB < -500) ppRadiusAB = -500;
                if (ppRadiusAB > 500) ppRadiusAB = 500;

                radiusPointAB.easting = pivot.easting + (ppRadiusAB * Math.Cos(localHeading));
                radiusPointAB.northing = pivot.northing + (ppRadiusAB * Math.Sin(localHeading));

                //Convert to millimeters
                distanceFromCurrentLinePivot = Math.Round(distanceFromCurrentLinePivot * 1000.0, MidpointRounding.AwayFromZero);

                //angular velocity in rads/sec  = 2PI * m/sec * radians/meters
                angVel = 0.277777 * mf.pn.speed * (Math.Tan(glm.toRadians(steerAngleAB))) / mf.vehicle.wheelbase;

                //clamp the steering angle to not exceed safe angular velocity
                if (Math.Abs(angVel) > mf.vehicle.maxAngularVelocity)
                {
                    steerAngleAB = glm.toDegrees(steerAngleAB > 0 ? (Math.Atan((mf.vehicle.wheelbase * mf.vehicle.maxAngularVelocity)
                        / (mf.pn.speed * 0.277777)))
                        : (Math.Atan((mf.vehicle.wheelbase * -mf.vehicle.maxAngularVelocity) / (mf.pn.speed * 0.277777))));
                }